Only released in EOL distros:
Package Summary
Gazebo's specific packages for RoboSavvy's balance platform.
- Maintainer status: maintained
- Maintainer: Vitor Matos <vmatos AT robosavvy DOT com>
- Author: Vitor Matos <vmatos AT robosavvy DOT com>
- License: BSD
- Source: git https://github.com/robosavvy/rsv_balance_simulator.git (branch: master)
Package Summary
Gazebo's specific packages for RoboSavvy's balance platform.
- Maintainer status: maintained
- Maintainer: Vitor Matos <vmatos AT robosavvy DOT com>
- Author: Vitor Matos <vmatos AT robosavvy DOT com>
- License: BSD
- Source: git https://github.com/robosavvy/rsv_balance_simulator.git (branch: master)
Contents
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:
empty.world - Empty world with only the robot.
roslaunch rsv_balance_gazebo simulation_empty.launch
ramp.world - Robot on inclined, flat terrain.
roslaunch rsv_balance_gazebo simulation_ramp.launch
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.
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 platformSubscribed Topics
/cmd_vel (geometry_msgs/Twist)- Velocity command input for differential drive type vehicle.
- Equilibrium point for the current state of the vehicle
Published Topics
/odom (nav_msgs/Odometry)- Publishes vehicle odometry
- Publishes self-balance control state
- Outputs wheel joint states if desired.
- Outputs odom and wheel transforms if desired
Services Called
/set_mode (rsv_balance_msgs/SetMode)- Service to set platform's operation mode.
- Service to set which input commands the vehicle. Not used in simulation.
- Service to reset odometry.
- 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
- Name for the velocity command topic
- Does the node publish odom tf?
- Base frame ID.
- Odometry frame ID.
- Odometry source. Odometry is computed from encoders or taken directly from world.
- Name for the odometry topic
- Does the node publish wheel joint state?
- Starting operation mode.
- Does the node publish self-balance control state?
- Rate for publishing self-balance control state.
- Rate for self-balance control loop.