Only released in EOL distros:  

rsv_balance_simulator: rsv_balance_gazebo

Package Summary

Gazebo's specific packages for RoboSavvy's balance platform.

rsv_balance_simulator: rsv_balance_gazebo

Package Summary

Gazebo's specific packages for RoboSavvy's balance platform.

Description

This package provides all the necessary URDF model extensions, worlds and launch files for successfully simulating RoboSavvy's self-balance platform.

On rsv_balance_gazebo package we have available 3 worlds:

  1. empty.world - Empty world with only the robot.

     roslaunch rsv_balance_gazebo simulation_empty.launch
  2. ramp.world - Robot on inclined, flat terrain.

     roslaunch rsv_balance_gazebo simulation_ramp.launch
  3. terrain.world - Robot on bumpy terrain.

     roslaunch rsv_balance_gazebo simulation_terrain.launch

As you can understand from the spawned robot, the demo model includes a dummy, spherical, 5kg load at about 1m height from the center of the platform.

simulation_tutorial1.png

It also provides RVIZ configured launchfile:

roslaunch rsv_balance_gazebo view.launch

Gazebo plugin node

The Gazebo model plugin was developed to expose the same ROS interface of topics and services as the real platform.

libgazebo_rsv_balance.so

Gazebo plugin for RoboSavvy's self-balance platform

Subscribed Topics

/cmd_vel (geometry_msgs/Twist)
  • Velocity command input for differential drive type vehicle.
/tilt_equilibrium (std_msgs/Float64)
  • Equilibrium point for the current state of the vehicle

Published Topics

/odom (nav_msgs/Odometry)
  • Publishes vehicle odometry
/state (rsv_balance_msgs/State)
  • Publishes self-balance control state
/joint_states (sensor_msgs/JointState)
  • Outputs wheel joint states if desired.
/tf (tf2_msgs/TFMessage)
  • Outputs odom and wheel transforms if desired

Services Called

/set_mode (rsv_balance_msgs/SetMode)
  • Service to set platform's operation mode.
/set_input (rsv_balance_msgs/SetInput)
  • Service to set which input commands the vehicle. Not used in simulation.
/reset_odom (std_srvs/Empty)
  • Service to reset odometry.
/reset_override (std_srvs/Empty)
  • Service to disable RC override. Not used in simulation.

Plugin parameters

Example configuration to include in your URDF model.

   1 <plugin name="rsv_balance_controller" filename="libgazebo_rsv_balance.so">
   2   <rosDebugLevel>Debug</rosDebugLevel>
   3   <!--<robotNamespace></robotNamespace>-->
   4   <commandTopic>cmd_vel</commandTopic>
   5   <baseFrameId>base_link</baseFrameId>
   6   <publishOdomTF>true</publishOdomTF>
   7   <odomFrameId>odom</odomFrameId>
   8   <odomSource>world</odomSource>
   9   <odomTopic>odom</odomTopic>
  10   <publishWheelJointState>true</publishWheelJointState>
  11   <!-- Platform specific configurations -->
  12   <startMode>balance</startMode>
  13   <publishState>true</publishState>
  14   <publishStateRate>1</publishStateRate>
  15   <publishDiagnosticsRate>1</publishDiagnosticsRate>
  16   <wheelSeparation>${base_width+2.*wheel_width/2.}</wheelSeparation>
  17   <wheelRadius>${wheel_radius}</wheelRadius>
  18   <leftJoint>base_to_left_wheel</leftJoint>
  19   <rightJoint>base_to_right_wheel</rightJoint>   
  20   <!-- Control specific configurations -->
  21   <updateRate>100</updateRate>
  22 </plugin>

Parameters

robotNamespace (str, default: "")
  • Robot's namespace
commandTopic (str, default: "cmd_vel")
  • Name for the velocity command topic
publishOdomTF (bool, default: false)
  • Does the node publish odom tf?
baseFrameId (str, default: "base_link")
  • Base frame ID.
odomFrameId (str, default: "odom")
  • Odometry frame ID.
odomSource (str, default: "world")
  • Odometry source. Odometry is computed from encoders or taken directly from world.
odomTopic (str, default: "odom")
  • Name for the odometry topic
publishWheelJointState (bool, default: false)
  • Does the node publish wheel joint state?
startMode (str, default: "balance")
  • Starting operation mode.
publishState (bool, default: false)
  • Does the node publish self-balance control state?
publishStateRate (int, default: 1)
  • Rate for publishing self-balance control state.
updateRate (int, default: 50)
  • Rate for self-balance control loop.

Wiki: rsv_balance_gazebo (last edited 2015-10-30 11:07:59 by RoboSavvy)