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

Provides an interface between ros and Rover Robotics rover hardware. Inputs to rr_openrover_driver include emergency stop and velocity commands. It outputs diagnostic data such as encoder readings and battery charge.

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

Provides an interface between ros and Rover Robotics rover hardware. Inputs to rr_openrover_driver include emergency stop and velocity commands. It outputs diagnostic data such as encoder readings and battery charge.

Description

This code is for those working with the Rover Robotics OpenRover. The OpenRover communicates via UART, this package abstracts away the UART communications and allows users to quickly get their robots moving around and doing cool things! We recommend using an FTDI cable which will convert the UART to USB for communicating with a computer.

rover_robotics_all_robots_1080_2.png

Running the example

roslaunch rr_openrover_driver example.launch

Reading Battery State of Charge

rostopic echo /rr_openrover_driver/r_slow_rate_data/reg_robot_rel_soc_a
rostopic echo /rr_openrover_driver/r_slow_rate_data/reg_robot_rel_soc_b

Sending Motors Commands

managed_pub = rospy.Publisher('/cmd_vel/managed', TwistStamped, queue_size=1)
managed_control_input.header.stamp = rospy.Time.now()
managed_control_input.header.frame_id = 'none'
managed_control_input.twist.linear.x=0.0
managed_control_input.twist.angular.y=0.0
managed_control_input.twist.angular.z=0.5
managed_pub.publish(managed_control_input)

Fusing Encoders with other sensors

We recommend using the robot_localization to fuse

Nodes

openrover_driver_node

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

Subscribed Topics

/cmd_vel/managed (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 need then this can be remapped to cmd_vel.
/rr_openrover_driver/fan_speed (std_msgs/Int32)
  • Controls the fan speed. It will override the fan speed set in the firmware. Use caution when setting fan speed manually, not having enough fan on time can burn out the motors or over heat the electronics.
/rr_openrover_driver/soft_estop/enable (std_msgs/Bool)
  • When set 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 like a pause button and autonomy can easily be resumed if the estop is reset before your navigation stack timeouts kick in.
/rr_openrover_driver/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

/rr_openrover_driver/odom_encoder (nav_msgs/Odometry)
  • Encoder-based odometry publishing at 10Hz.
/rr_openrover_driver/raw_fast_rate_data (invalid message type for MsgLink(msg/type))
  • (DEPRECATED) custom message at 30Hz that contains the encoder values for the following: header, left_motor, right_motor, flipper_motor.
/rr_openrover_driver/raw_med_rate_data (invalid message type for MsgLink(msg/type))
  • (DEPRECATED) custom message at 2Hz that contains the following data: header, reg_pwr_total_current, reg_motor_fb_rpm_left, reg_motor_fb_right, reg_flipper_fb_position_pot1, reg_flipper_fb_position_pot2, reg_motor_fb_current_left, reg_motor_fb_current_right, reg_motor_charger_state, reg_power_a_current, reg_power_b_current, reg_motor_flipper_angle.
/rr_openrover_driver/raw_slow_rate_data (invalid message type for MsgLink(msg/type))
  • (DEPRECATED) 1Hz custom message that contains the following data: header, reg_motor_fault_flag_left, reg_motor_temp_left, reg_motor_temp_right, reg_power_bat_voltage_a, reg_power_bat_voltage_b, reg_robot_rel_soc_a, reg_robot_rel_soc_b, buildno.
/rr_openrover_driver/battery_status_a (invalid message type for MsgLink(msg/type))
  • Status message of Cell A
/rr_openrover_driver/battery_status_b (invalid message type for MsgLink(msg/type))
  • Status message of Cell B

Parameters

~use_legacy (bool, default: false)
  • Publish the deprecated state messages raw_fast_rate_data, raw_med_rate_data, and raw_slow_rate_data when set to true.
~port (string, default: "/dev/ttyUSB0")
  • The port used for UART communication. It is recommended to use an FTDI cable to communicate with the robot. When the FTDI cable is plugged into a linux system it will enumerate as /dev/ttyUSBx, where x is the lowest number not currently in use. This means that if the robot gets uplugged and replugged in this value may change. It is recommended to setup a udev rule for the robot that will always name it something like /dev/rover and to set this parameter to the same thing so that if it gets unplugged and replugged in things will work still.
~fast_data_rate (int, default: 10)
  • Rate at which the computer polls the robot for data categorized as fast
~med_data_rate (int, default: 2)
  • Rate at which the computer polls the robot for data categorized as med
~slow_data_rate (int, default: 1)
  • Rate at which the computer polls the robot for data categorized as slow
~closed_loop_control_on (Bool, default: 'False')
  • Turns on a PID controller to match wheel speeds to commanded values
~timeout (float, default: 0.5)
  • If enable_timeout is set to true timeout is the amount of time in seconds the driver will wait for data to be published to /cmd_vel/managed before stopping the robot.
~total_weight (float, default: 20.0)
  • (Effects accuracy of /rr_openrover_driver/odom_encoder). The total weight of the robot in pounds.
~drive_type (string, default: "4wd")
  • (Effects accuracy of /rr_openrover_driver/odom_encoder) Sets the robot's wheel configuration. The three options are flippers, 4wd, and 2wd. This param is important to set properly for the odom to be reported properly.
~kp (int, default: 40)
  • proportional gain of PID controller
~ki (int, default: 100)
  • integral gain of PID controller
~kd (int, default: 0)
  • derivative gain of PID controller
~traction_factor (float, default: depends on drive type chosen)
  • (Effects accuracy of /rr_openrover_driver/odom_encoder). This helps the odometry from encoders be more accurate when using a 4WD of flipper robot. The wheels slip a certain amount, this parameter can be adjusted between 0 and 1 to account for the slippage. Default for 2WD is 0.9877, default for 4WD is 0.610, default for flippers is 0.98.
~odom_covariance_0 (float, default: 0.01)
  • The driving straight covariance for the encoder odometry
~odom_covariance_35 (float, default: 0.03)
  • The turning covariance for the encoder odometry

Running

Example using rosrun

rosrun rr_openrover_driver openrover_driver_node

Example launch file

<launch>
    <arg name="openrover_node_name" default="rr_openrover_driver"/>

    <!-- OpenRover Driver -->
    <node pkg="rr_openrover_driver" type="openrover_driver_node" name="$(arg openrover_node_name)" respawn="false" output="screen">
        <param name="port" value="/dev/rover" />
        <param name="drive_type" value="4wd" />
        <param name="enable_timeout" type="bool" value="true"/>
        <param name="timeout" type="double" value="0.3"/>
        <param name="total_weight" type="double" value="20.41"/>
        <param name="traction_factor" value="0.610"/>
        <param name="odom_covariance_0" value="0.01"/>
        <param name="odom_covariance_35" value="0.03"/>
    </node>

    <!-- OpenRover Diagnostics -->
    <node pkg="rr_openrover_driver" type="diagnostics.py" name="rr_openrover_diagnostics_node">
        <remap from="/raw_slow_rate_data" to="/$(arg openrover_node_name)/raw_slow_rate_data"/>
    </node>
</launch>slow_rate_pub

Release Notes

This package is currently in pre-release meaning the code has been tested and is functional, but backwards compatibility is not guaranteed until v1.0.0, so make note of which version you are using and read the changelog carefully before updating.

Wiki: rr_openrover_driver (last edited 2020-08-22 00:20:01 by nickfragale)