ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

joystick output not reliable

asked 2018-01-08 04:05:30 -0500

updated 2018-01-09 02:46:49 -0500

gvdhoorn gravatar image

Using joystick to drive turtlesim, he goes a ways then stops. If I move the stick a bit, he'll start up again. This may be a similar problem to seeing the numbers zero out when I run a full robot stack, with ROS_controls, and echo cmd_vel output to the terminal. Numbers look good for five seconds but then go to zero at unexpected times and at different stick angles. Is ROS failing me or is it the hardware? Using jstest the numbers stay looking good. Is it a problem with the publishing rate in hertz?


Edit:

<launch>
    <node pkg="turtlesim" type="turtlesim_node" name="turtlesim" respawn="true"/>
    <node pkg="teleop_twist_joy" type="teleop_node" name="teleop_twist_joy">
        <remap from="cmd_vel" to="turtle1/cmd_vel"/>
    </node>
    <node pkg="joy" type="joy_node" name="joy_node"/>
</launch>

The above is for the turtlesim test. The stack for actual robot is RosJet from here: https://github.com/NVIDIAGPUTeachingK... .

Thanks for help!

edit retag flag offensive close merge delete

Comments

1

This sounds to me like a joystick device being opened in 'event mode' and using a motion controller with an integrated (and enabled) command time-out (ie: no new Twist in X sec -> stop).

Can you describe the full setup you have? Which nodes are involved in the teleop dataflow?

gvdhoorn gravatar image gvdhoorn  ( 2018-01-08 04:16:07 -0500 )edit

I've moved your comments to your original question, as comments are not suited for showing launch files. Please always update your original question in these cases using the edit button/link.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-09 03:00:58 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2018-01-09 02:54:42 -0500

gvdhoorn gravatar image

updated 2018-01-09 03:07:56 -0500

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, 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).

edit flag offensive delete link more

Comments

That makes sense! I'll try this out as soon as I get back to the robot shop. Thanks!

Rodolfo8 gravatar image Rodolfo8  ( 2018-01-10 03:40:14 -0500 )edit

Yes, that was it. Added two lines of parameters and it works perfectly. Thanks. I removed those lines earlier (from joy and teleop launch sections) because the software wouldn't work at all, and after removing the parameters, it started working for the first time.

Rodolfo8 gravatar image Rodolfo8  ( 2018-01-10 21:28:42 -0500 )edit

Now I need to figure out why the motor commands from the Arduino often contain garbage and therefore don't control the motors well. Maybe it's because the encoders aren't connected up yet.

Rodolfo8 gravatar image Rodolfo8  ( 2018-01-10 21:32:41 -0500 )edit

That would seem to be a different issue.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-11 02:04:10 -0500 )edit

Added two lines of parameters and it works perfectly.

note btw that the teleop_twist_joy launch file does more: it also loads a yaml file that configures teleop_twist_joy with quite some additional parameters.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-11 02:05:14 -0500 )edit

Got the motors to perform! Turns out the Sabertooth Arduino libraries are not compatible with ROS. Program the direct serial writes instead and you're good to go.

Rodolfo8 gravatar image Rodolfo8  ( 2018-01-14 16:27:05 -0500 )edit

This helped me a lot! Thanks @gvdhoorn.

Marcus Barnet gravatar image Marcus Barnet  ( 2020-05-02 13:36:17 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-01-08 04:05:30 -0500

Seen: 1,229 times

Last updated: Jan 09 '18