diff --git a/launch/teleop_keyboard.launch b/launch/teleop_keyboard.launch index 28374de267953ae9107cefd3e2828bd8c8ce3a3e..3e46f20b80c50a1d0cfb90cf471f50829dcb56e6 100644 --- a/launch/teleop_keyboard.launch +++ b/launch/teleop_keyboard.launch @@ -1,6 +1,6 @@ <launch> - <node pkg="teleop_twist_keyboard" name="teleop_twist_keyboard" type="teleop_twist_keyboard.py"> + <node pkg="teleop_twist_keyboard" name="teleop_twist_keyboard" type="teleop_twist_keyboard.py" output="screen"> </node> <include file="$(find twist_to_manual_control)/launch/node.launch"/> diff --git a/src/twist_to_manual_control_alg_node.cpp b/src/twist_to_manual_control_alg_node.cpp index 2eb461e0cd3bd0d7496fd14aef5894cf978a634c..e4825dcd127bcb9eb7131d34efb29a39f4b80207 100644 --- a/src/twist_to_manual_control_alg_node.cpp +++ b/src/twist_to_manual_control_alg_node.cpp @@ -65,12 +65,23 @@ void TwistToManualControlAlgNode::cmd_vel_callback(const geometry_msgs::Twist::C //this->alg_.lock(); //this->cmd_vel_mutex_enter(); + // NewValue = (((OldValue - OldMin)*(NewMax - NewMin)) / (OldMax - OldMin)) + NewMin double angular = msg->angular.z; - // NewValue = (((OldValue - OldMin ) * (NewMax - NewMin)) / (OldMax - OldMin)) + NewMin + if (angular > this->config_.angular_sat_max) + angular=this->config_.angular_sat_max; + + if (angular < this->config_.angular_sat_min) + angular=this->config_.angular_sat_min; + int steering = (((angular - this->config_.angular_sat_min) * (this->config_.steering_max - this->config_.steering_min)) / (this->config_.angular_sat_max - this->config_.angular_sat_min)) + this->config_.steering_min; double linear = msg->linear.x; - //NewValue = (((OldValue - OldMin ) * (NewMax - NewMin)) / (OldMax - OldMin)) + NewMin + if (linear > this->config_.linear_sat_max) + linear=this->config_.linear_sat_max; + + if (linear < this->config_.linear_sat_min) + linear=this->config_.linear_sat_min; + int speed = (((linear - this->config_.linear_sat_min) * (this->config_.speed_max - this->config_.speed_min)) / (this->config_.linear_sat_max - this->config_.linear_sat_min)) + this->config_.speed_min;