Show EOL distros: 

rr_openrover_stack: rr_control_input_manager | rr_openrover_description | rr_openrover_driver | rr_openrover_driver_msgs | rr_openrover_simulation | rr_rover_zero_driver

Package Summary

The rover_zero_driver package

Description

This code is for those working with the Rover Robotics Rover Zero V1.

rover-robotics-rover-zero_1024x.jpg

The Rover Zero V1 uses the RoboClaw 2x15 motor controller which communicates via USB.

roboclaw-rover-robotics.jpg

This package abstracts away the USB communications and allows users to quickly get their robots moving around and doing cool things!

Nodes

rr_roverzero_driver

This package serves as a ROS driver for a Rover Robotics Rover Zero Driver which communicates via UART to a host PC running ROS. This package assumes users are using a USB cable.

Subscribed Topics

/cmd_vel (geometry_msgs/Twist)
  • A topic that controls the linear (m/s) and angular (rad/s) velocity of the robot. cmd_vel/managed should come from a package that can manage multiple sources of control (local joystick, remote keyboard, move_base, etc...) like rr_control_manager. If only one source of input is needed then this can be remapped to cmd_vel.
soft_estop/enable (std_msgs/Bool)
  • When set to True the driver will ignore all input commands until the True message is received on the /rr_openrover_driver/soft_estop/reset topic (even if False is published to this topic). This is very useful to map to a button on a controller. If activated while using the ROS nav stack it acts as a pause button and autonomy can easily be resumed if the estop is reset before your navigation stack timeouts kick in.
soft_estop/reset (std_msgs/Bool)
  • Used to reset the soft_estop. This is also useful to map to a button on a controller

Published Topics

diagnostics (<<MsgLink: execution failed [string index out of range] (see also the log)>>)
  • diagnostics settings for roboclaw.
odom (invalid message type for MsgLink(msg/type))
  • Encoder-based odometry

Parameters

address (int, default: 128)
  • Roboclaw communication address
baud (int, default: 115200)
  • commuincation baudrate
max_vel (double, default: 5)
  • software cap on robot's velocity
max_turn_rate (double, default: 6.28)
  • software cap on robot's turnrate
speed_to_duty_coef (double, default: 1.02)
  • coeficient used to convert speed to duty cycle
diag_frequency_hz (double, default: 1.0)
  • diagnostic frequency
motor_cmd_frequency_hz (double, default: 30)
  • motor cmd frequency
odom_frequency_hz (double, default: 30)
  • odometry frequency
cmd_vel_timeout (double, default: .5)
  • roboclaw communication timeout
enable_encoder_odom (Bool, default: False)
  • enable to publish odometry data to ros
enable_esc_feedback_controls (Bool, default: False)
  • Enable to turn on PID with current PID settings. Will ignore PID values from PID parameters
v_pid_overwrite (Bool, default: False)
  • Overwrite Hardware PID values with the one from PID parameters
save_motor_controller_settings (Bool, default: false)
  • save changes to motor controller
m1_v_p (Double, default: 3)
  • Motor 1 Velocity P
m1_v_i (Double, default: 0.35)
  • Motor 1 Velocity I
m1_v_d (Double, default: 0)
  • Motor 1 Velocity D
m1_v_qpps (Int, default: 10000)
  • Motor 1 Maximum Possible Speed*
m2_v_p (Double, default: 3)
  • Motor 2 Velocity P
m2_v_i (Double, default: 0.35)
  • Motor 2 Velocity I
m2_v_d (Double, default: 0)
  • Motor 2 Velocity D
m2_v_qpps (Int, default: 10000)
  • Motor 2 Maximum Possible Speed
encoder_pulses_per_turn (Double, default: 5400)
  • Encoder Tick Per Revolution
left_motor_max_current (Double, default: 5)
  • Motor 1 Max Current Setting
right_motor_max_current (Double, default: 5)
  • Motor 2 Max Current Setting
active_brake_timeout (double, default: 1)
  • Active brake timeout
odom_frame (tf, default: odom)
  • Robot TF Frame for Odometry
base_link_frame (tf, default: base_link)
  • Robot TF Frame for Base Link
wheel_base (double, default: 0.358775)
  • Distance between center of wheels
wheel_radius (Double, default: 0.127)
  • Radius of wheel

Wiki: rr_rover_zero_driver (last edited 2020-07-28 14:16:38 by nickfragale)