[Documentation] [TitleIndex] [WordIndex

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

Installation

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

We currently only support ROS Kinetic,

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) /rr_openrover_basic/fan_speed (std_msgs/Int32)

Published Topics

/rr_openrover_basic/odom_encoder (nav_msgs/Odometry) /rr_openrover_basic/raw_fast_rate_data (invalid message type for MsgLink(msg/type)) /rr_openrover_basic/raw_med_rate_data (invalid message type for MsgLink(msg/type)) /rr_openrover_basic/raw_slow_rate_data (invalid message type for MsgLink(msg/type)) /rr_openrover_basic/battery_status_a (invalid message type for MsgLink(msg/type)) /rr_openrover_basic/battery_status_b (invalid message type for MsgLink(msg/type))

Parameters

~port (string, default: "/dev/ttyUSB0") ~enable_timeout (bool, default: true) ~timeout (float, default: 0.5) ~drive_type (string, default: "4wd") ~total_weight (float, default: 20.0) ~traction_factor (float, default: depends on drive type chosen) ~odom_covariance_0 (float, default: 0.01) ~odom_covariance_35 (float, default: 0.03)

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="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 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.


2019-10-12 13:06