66 */
77
88#include < vb_util_lib/rc_controls.h>
9+ #include < vb_util_lib/rc_mapper.h>
910#include < vb_util_lib/topics.h>
1011
1112using namespace am ;
@@ -52,13 +53,15 @@ RC_Controls::~RC_Controls() {
5253 // TODO Auto-generated destructor stub
5354}
5455
55- RC_Controls::RC_Controls (ros::NodeHandle& n, RC_TYPE type) : rc_type_(type) {
56+ RC_Controls::RC_Controls (ros::NodeHandle& n, RC_TYPE type) : rc_type_(type)
57+ {
58+ rc_mapper_ = new rc_mapper (n);
5659 setSubscriber (n);
5760}
5861
5962void RC_Controls::setSubscriber (ros::NodeHandle& n) {
6063 // Initialize the min and max constants
61- n.param (" /RC/max_value" , MAX_VALUE_, MAX_VALUE_);
64+ /* n.param("/RC/max_value", MAX_VALUE_, MAX_VALUE_);
6265 n.param("/RC/min_value", MIN_VALUE_, MIN_VALUE_);
6366
6467 std::string rc_type;
@@ -101,10 +104,10 @@ void RC_Controls::setSubscriber(ros::NodeHandle& n) {
101104 mode_idx_ = ACSL_MODE;
102105 arm_idx_ = ACSL_ARM;
103106
104- throttle_sign = ACSL_THROTTLE_SIGN;
105- yaw_sign = ACSL_YAW_SIGN;
106- roll_sign = ACSL_ROLL_SIGN;
107- pitch_sign = ACSL_PITCH_SIGN;
107+ throttle_sign_ = ACSL_THROTTLE_SIGN;
108+ yaw_sign_ = ACSL_YAW_SIGN;
109+ roll_sign_ = ACSL_ROLL_SIGN;
110+ pitch_sign_ = ACSL_PITCH_SIGN;
108111
109112 break;
110113
@@ -120,13 +123,33 @@ void RC_Controls::setSubscriber(ros::NodeHandle& n) {
120123 mode_idx_ = PX4_MODE;
121124 arm_idx_ = PX4_ARM;
122125
123- throttle_sign = PX4_THROTTLE_SIGN;
124- yaw_sign = PX4_YAW_SIGN;
125- roll_sign = PX4_ROLL_SIGN;
126- pitch_sign = PX4_PITCH_SIGN;
126+ throttle_sign_ = PX4_THROTTLE_SIGN;
127+ yaw_sign_ = PX4_YAW_SIGN;
128+ roll_sign_ = PX4_ROLL_SIGN;
129+ pitch_sign_ = PX4_PITCH_SIGN;
127130
128131 break;
129- }
132+ }*/
133+
134+ rc_type_ = static_cast <RC_TYPE>(rc_mapper_->GetSetRC ());
135+
136+ MIN_VALUE_ = rc_mapper_->GetMin ();
137+ MAX_VALUE_ = rc_mapper_->GetMax ();
138+
139+ throttle_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCThrottle);
140+ yaw_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCYaw);
141+ roll_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCRoll);
142+ pitch_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCPitch);
143+ gear_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCGear);
144+ mode_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCMode);
145+ arm_idx_ = rc_mapper_->GetChannel (rc_mapper::eRCArm);
146+
147+ throttle_sign_ = rc_mapper_->GetSign (rc_mapper::eThrottleSign);
148+ yaw_sign_ = rc_mapper_->GetSign (rc_mapper::eRCYaw);
149+ roll_sign_ = rc_mapper_->GetSign (rc_mapper::eRollSign);
150+ pitch_sign_ = rc_mapper_->GetSign (rc_mapper::eRCPitch);
151+
152+ ROS_INFO (" RC: RC Param Settings: throttle[%d], yaw[%d], roll[%d], pitch[%d], gear[%d], mode[%d], arm[%d], throttle_sign_[%d], yaw_sign_[%d], roll_sign_[%d], pitch_sign_[%d], max[%d], min[%d]" , throttle_idx_, yaw_idx_, roll_idx_, pitch_idx_, gear_idx_, mode_idx_, arm_idx_, throttle_sign_, yaw_sign_, roll_sign_, pitch_sign_, MAX_VALUE_, MIN_VALUE_);
130153
131154 RANGE_ = ((MAX_VALUE_ - MIN_VALUE_)/2 );
132155 ZERO_VALUE_ = (MIN_VALUE_ + RANGE_);
@@ -151,12 +174,19 @@ void RC_Controls::setDJIControls(const sensor_msgs::Joy::ConstPtr& msg) {
151174 stamp = msg->header .stamp ;
152175
153176 // Set the raw values;
154- throttle_ = msg->axes [3 ];
177+ /* throttle_ = msg->axes[3];
155178 yaw_ = msg->axes[2];
156179 pitch_ = msg->axes[1];
157180 roll_ = msg->axes[0];
158181 gear_ = msg->axes[5];
159- mode_ = msg->axes [4 ];
182+ mode_ = msg->axes[4];*/
183+
184+ throttle_ = msg->axes [throttle_idx_];
185+ yaw_ = msg->axes [yaw_idx_];
186+ pitch_ = msg->axes [pitch_idx_];
187+ roll_ = msg->axes [roll_idx_];
188+ gear_ = msg->axes [gear_idx_];
189+ mode_ = msg->axes [mode_idx_];
160190
161191 setDJIStickValue (yaw_, yaw);
162192 setDJIStickValue (pitch_, pitch);
@@ -259,10 +289,10 @@ void RC_Controls::setPX4Controls(const mavros_msgs::RCIn::ConstPtr& msg) {
259289 mode_ = msg->channels [mode_idx_];
260290 armed_ = msg->channels [arm_idx_];
261291
262- setPX4StickValue (yaw_, yaw, yaw_sign );
263- setPX4StickValue (pitch_, pitch, pitch_sign );
264- setPX4StickValue (roll_, roll, roll_sign );
265- setPX4StickValue (throttle_, throttle, throttle_sign );
292+ setPX4StickValue (yaw_, yaw, yaw_sign_ );
293+ setPX4StickValue (pitch_, pitch, pitch_sign_ );
294+ setPX4StickValue (roll_, roll, roll_sign_ );
295+ setPX4StickValue (throttle_, throttle, throttle_sign_ );
266296
267297 setPX4ModeSwitch (mode_, mode);
268298 setPX4GearSwitch (gear_, gear);
0 commit comments