Package Summary

The rr_openrover_basic package

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 allow 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

Installation

sudo apt-get install ros-kinetic-rr-openrover-basic

Running the example

roslaunch rr_openrover_basic example.launch

Reading Battery State of Charge

rostopic echo /rr_openrover_basic/r_slow_rate_data/reg_robot_rel_soc_a
rostopic echo /rr_openrover_basic/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_basic_node

This package serves as a ROS driver for a Rover Robotics OpenRover basic 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_basic/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.

Published Topics

/rr_openrover_basic/odom_encoder (nav_msgs/Odometry)
  • Encoder-based odometry publishing at 10Hz.
/rr_openrover_basic/raw_fast_rate_data (invalid message type for MsgLink(msg/type))
  • custom message at 30Hz that contains the encoder values for the following: header, left_motor, right_motor, flipper_motor.
/rr_openrover_basic/raw_med_rate_data (invalid message type for MsgLink(msg/type))
  • 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_basic/raw_slow_rate_data (invalid message type for MsgLink(msg/type))
  • 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_basic/battery_status_a (invalid message type for MsgLink(msg/type))
  • Status message of Cell A
/rr_openrover_basic/battery_status_b (invalid message type for MsgLink(msg/type))
  • Status message of Cell B

Parameters

~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.
~drive_type (string, default: "flippers")
  • 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.
~enable_timeout (bool, default: true)
  • If enabled this driver will stop the robot if nothing new is published to cmd_vel/managed in the timeout window. Its highly recommended that this be set to true.
~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.
~default_low_speed_mode (bool, default: true)
  • If enabled, the robot will start in low speed mode allowing for much better low speed control.

Running

Example using rosrun

rosrun rr_openrover_basic openrover_basic_node

Example launch file

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

    <!-- OpenRover Driver -->
    <node pkg="rr_openrover_basic" type="openrover_basic_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="closed_loop_control_on" type="bool" value="false" />
        <param name="total_weight" type="double" value="20.41"/>
        <param name="slippage_factor" value="0.610"/>
        <param name="odom_covariance_0" value="0.01"/>
        <param name="odom_covariance_35" value="0.03"/>
    </node>

    <!-- OpenRover InOrbit Diagnostics -->
    <node pkg="rr_openrover_basic" 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>

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_basic (last edited 2018-12-12 16:11:44 by nickfragale)