ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
If that is your launch file, I believe you are missing some important parameters for this to work correctly.
The launch file for teleop_twist_joy
sets (among others) the autorepeat_rate
parameter for the joy_node
node, which is probably what is causing the issues here.
Is it a problem with the publishing rate in hertz?
In a way: yes. Without autorepeat_rate
, joysticks in event mode will not cause any msgs to be sent without any changes being detected to any of the axes. If you maintain stick position (ie: angles), nothing will change (due to filtering/deadzone), causing no msgs to be published. No messages -> auto stop (in well-written mobile base drivers, that is).
From the joy wiki page:
~autorepeat_rate
(double
, default: 0.0 (disabled))Rate in Hz at which a joystick that has a non-changing state will resend the previously sent message.
I would recommend to alter your launch file to include
the teleop_twist_joy/launch/teleop.launch
file, instead of starting the node directly. That will set all parameters as they should be, and things should start working a whole lot better. See also the teleop_twist_joy documentation on the ROS wiki.
Including provided launch files is in general always a good strategy btw, as typically launch files configure parameters that the node needs. Defaults can work, but they are always going to be sub-optimal.
2 | No.2 Revision |
If that is your launch file, I believe you are missing some important parameters for this to work correctly.
The launch file for teleop_twist_joy
sets (among others) the autorepeat_rate
parameter for the joy_node
node, which is probably what is causing the issues here.
Is it a problem with the publishing rate in hertz?
In a way: yes. Without autorepeat_rate
, joysticks in event mode will not cause any msgs to be sent without any changes being detected to any of the axes. If you maintain stick position (ie: angles), nothing will change (due to filtering/deadzone), causing no msgs to be published. No messages -> auto stop (in well-written mobile base drivers, that is).
From the joy wiki page:
~autorepeat_rate
(double
, default: 0.0 (disabled))Rate in Hz at which a joystick that has a non-changing state will resend the previously sent message.
I would recommend to alter your launch file to include
the teleop_twist_joy/launch/teleop.launch
file, instead of starting the node directly. That will set all parameters as they should be, and things should start working a whole lot better. See also the teleop_twist_joy documentation on the ROS wiki.
Including provided launch files is in general always a good strategy btw, as typically launch files configure parameters that the node needs. Defaults can work, but they are always going to be sub-optimal.
Edit: and if you want to go a step further, you could look into including some of the packages from the Turtlebot, such as yocs_cmd_vel_mux (multiplexing between different Twist
sources) and yocs_velocity_smoother (filter for Twist
inputs).
3 | No.3 Revision |
If that is your launch file, I believe you are missing some important parameters for this to work correctly.
The launch file for teleop_twist_joy
sets (among others) the autorepeat_rate
parameter for the joy_node
node, which is probably what is causing the issues here.
Is it a problem with the publishing rate in hertz?
In a way: yes. Without autorepeat_rate
, joysticks in event mode will not cause any msgs to be sent without any changes being detected to any of the axes. If you maintain stick position (ie: angles), nothing will change (due to filtering/deadzone), causing no msgs to be published. No messages -> auto stop (in well-written mobile base drivers, that is).
From the joy wiki page:
~autorepeat_rate
(double
, default: 0.0 (disabled))Rate in Hz at which a joystick that has a non-changing state will resend the previously sent message.
I would recommend to alter your launch file to include
the teleop_twist_joy/launch/teleop.launch
file, instead of starting the node directly. directly (note that you also don't need to start the joy_node
itself anymore in that case). That will set all parameters as they should be, and things should start working a whole lot better. See also the teleop_twist_joy documentation on the ROS wiki.
Including provided launch files is in general always a good strategy btw, as typically launch files configure parameters that the node needs. Defaults can work, but they are always going to be sub-optimal.
Edit: and if you want to go a step further, you could look into including some of the packages from the Turtlebot, such as yocs_cmd_vel_mux (multiplexing between different Twist
sources) and yocs_velocity_smoother (filter for Twist
inputs).
4 | No.4 Revision |
If that is your launch file, I believe you are missing some important parameters for this to work correctly.
The launch file for teleop_twist_joy
sets (among others) the autorepeat_rate
parameter for the joy_node
node, which is probably what is causing the issues here.
Is it a problem with the publishing rate in hertz?
In a way: yes. Without autorepeat_rate
, joysticks in event mode will not cause any msgs to be sent without any changes being detected to any of the axes. If you maintain stick position (ie: angles), nothing will change (due to filtering/deadzone), causing no msgs to be published. No messages -> auto stop (in well-written mobile base drivers, that is).is, see here for how this is implemented in turtlesim
).
From the joy wiki page:
~autorepeat_rate
(double
, default: 0.0 (disabled))Rate in Hz at which a joystick that has a non-changing state will resend the previously sent message.
I would recommend to alter your launch file to include
the teleop_twist_joy/launch/teleop.launch
file, instead of starting the node directly (note that you also don't need to start the joy_node
itself anymore in that case). That will set all parameters as they should be, and things should start working a whole lot better. See also the teleop_twist_joy documentation on the ROS wiki.
Including provided launch files is in general always a good strategy btw, as typically launch files configure parameters that the node needs. Defaults can work, but they are always going to be sub-optimal.
Edit: and if you want to go a step further, you could look into including some of the packages from the Turtlebot, such as yocs_cmd_vel_mux (multiplexing between different Twist
sources) and yocs_velocity_smoother (filter for Twist
inputs).