<> <> == Preliminary Setup == First make sure you have the latest ric meta-package installed. See [[ric#Installation|Installation Instructions]] on the ric page. Then, install additional packages: {{{ $ sudo apt-get install ros-indigo-gazebo-ros-pkgs ros-indigo-gazebo-ros-control ros-indigo-hector-gazebo ros-indigo-ros-controllers }}} == Launch == To launch the simulation with default parameters run the specific robot simulation launch file: {{{ $ roslaunch ric_gazebo komodo_gazebo.launch }}} or: {{{ $ roslaunch ric_gazebo lizi_gazebo.launch }}} or: {{{ $ roslaunch ric_gazebo komodo_with_elev_gazebo.launch }}} To change the robot color, name, initial position and orientation and sensors edit the robot spawn block in the simulation launch file: {{{ Here is and example of the Komodo robot launched with default settings: }}} {{attachment:gazeboo.png|alt text|width="600"}} To launch multiple robots in the same simulation add another block on the launch file as bellow: {{{ }}} {{attachment:gazeboo2.png|alt text|width="600"}} You can view the robots sensors using rviz: {{attachment:rviz.png|alt text|width="600"}} == Topics that are good to know (only komodo models) == === Subscribers === 1. komodo_/base_rotation_controller/command * Function: Rotate the arm. * Msg type: std_msgs/Float64 1. komodo_/shoulder_controller/command * Function: Move the shoulder of the arm up and down. * Msg type: std_msgs/Float64 1. komodo_/elbow1_controller/command * Function: Move the first elbow of the arm left and right. * Msg type: std_msgs/Float64 1. komodo_/elbow2_controller/command * Function: Move the second elbow of the arm up and down. * Msg type: std_msgs/Float64 1. komodo_/wrist_controller/command * Function: Rotate the wrist left and right. * Msg type: std_msgs/Float64 1. komodo_/right_finger_controller/command * Function: move the right finger, left or right. * Msg type: std_msgs/Float64 1. komodo_/left_finger_controller/command * Function: move the left finger, left or right. * Msg type: std_msgs/Float64 1. komodo_/diff_driver/command * Function: steering the robot. * Msg type: geometry_msgs/Twist '''Subscribers that are only present in the komodo with elevator and arm''' 1. komodo_/elevator_controller/command * Function: Move the komodo elevator up and down. * Msg type: std_msgs/Float64 === Publishers === 1. komodo_/scan * Function: Publish the laser scan. * Msg type: sensor_msgs/LaserScan 1. komodo_/arm_camera/image_raw * Function: Publish images from the arm camera. * Msg type: sensor_msgs/Image 1. komodo_/Front_Camera/image_raw * Function: Publish images from the front camera. * Msg type: sensor_msgs/Image 1. komodo_/diff_driver/odometry * Function: Publish the odometry of the robot. * Msg type: nav_msgs/Odometry '''Publishers that are only prasent in the komodo with elevator and arm''' 1. komodo_/Creative_Camera/rgb/image_raw * Function: Publish images from the arm camera. * Msg type: sensor_msgs/Image 1. komodo_/Creative_Camera/depth/image_raw * Function: Publish a depth images from the arm camera. * Msg type: sensor_msgs/Image 1. komodo_/Asus_Camera/rgb/image_raw * Function: Publish images from the top asus camera. * Msg type: sensor_msgs/Image 1. komodo_/Asus_Camera/depth/image_raw * Function: Publish a depth images from the asus camera * Msg type: sensor_msgs/Image 1. komodo_/rear_camera/image_raw * Function: Publish images from the rear camera. * Msg type: sensor_msgs/Image 1. komodo_/top_camera/image_raw * Function: Publish images from the top camera * Msg type: sensor_msgs/Image == Moveit with ric_gazebo == === Launch === To launch the komodo with arm model type this commend in a new terminal: {{{ $ roslaunch komodo_2_moveit_config komodo_gazebo_moveit.launch }}} To launch the komodo with elevator and arm model type this commend in a new terminal: {{{ $ roslaunch komodo_arm_moveit_config komodo_with_elev_gazebo_moveit.launch }}} == Videos == <> Komodo with arm running moveit <> Komodo with arm and elevator running moveit <> == Troubleshoot == If you see something like this after launching: {{{ Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Warning [gazebo.cc:215] Waited 1seconds for namespaces. Error [gazebo.cc:220] Waited 11 seconds for namespaces. Giving up. }}} Try to upgrade to gazebo 2.2.5: {{{ > sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu trusty main" > /etc/apt/sources.list.d/gazebo-latest.list' > wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add - }}} Then if you update Ubuntu, It install Gazebo 2.2.5. ## AUTOGENERATED DON'T DELETE ## CategoryPackage