Simulation¶
Unitree A1 supports two different development environment Gazebo and Webots, with which a virtual robot in the simulation can be programmed for testing in real world virtual evironments. Both simulators Gazebo and Webots are simulated with a fake node and visualization tool RViz is used.
Both simulators support different sensors like IMUs, lidars, cameras and many more. With these simulators and sensors autonomous navigation, slam and other functionalities can be tested.
In this instruction, Gazebo will be introduced which is most widely used among ROS developers. Later Webots will be introduced which is quite robust, easy to use and is more realistic.
Gazebo Tutorials: http://gazebosim.org/tutorials
Webots Tutorials: https://cyberbotics.com/doc/guide/tutorials
Gazebo¶
qre_a1_gazebo & qre_controller¶
qre_a1_gazebo package contains the Gazebo simulation for the A1 robot. The robot can be teleoperated and can be used further for slam and autonomous navigation. This package is dependent upon qre_controller which contains several low level robot controllers state_estimator, quadruped_controller and contact_sensor.
To launch Gazebo run the following command:
roslaunch qre_a1_gazebo gazebo.launch
This launch file runs all the necessary controllers and accept commands in cmd_vel(geometry_msgs/Twist). The same package qre_controller can be used to verify the robot movements in RVIZ. To do so run the following command:
roslaunch qre_a1_description bringup.launch rviz:=true ll_control:=true
Now by running any teleop node the robot can be controlled.
unitree_gazebo & unitree_controller:¶
You can launch the Gazebo simulation by the following command:
roslaunch unitree_gazebo normal.launch rname:=a1 wname:=stairs
Where the rname
means robot name, which can be laikago
,
aliengo
or a1
. The wname
means world name, which can be
earth
, space
or stairs
(for stairs world don’t forget to
change the respective world as described
here). And
the default value of rname
is laikago
, while the default value
of wname
is earth
. In Gazebo, the robot should be lying on the
ground with joints not activated.
Stand controller¶
After launching the gazebo simulation, you can start to control the robot:
rosrun unitree_controller unitree_servo
And you can add external disturbances, like a push or a kick:
rosrun unitree_controller unitree_external_force
Position and pose publisher¶
Here we showed how to control the position and pose of robot without a controller, which should be useful in SLAM or visual development.
Then run the position and pose publisher in another terminal:
rosrun unitree_controller unitree_move_kinetic
The robot will turn around the origin, which is the movement under the
world coordinate. And inside of the source file move_publisher
, we
also offered the method to move robot under robot coordinate. You can
change the value of def_frame
to coord::ROBOT
and run the
catkin_make again, then the unitree_move_publisher
will move robot
under its own coordinate.
Webots¶
qre_a1_wbsim¶
qre_a1_wbsim contains Webots simulator file for Unitree A1. In the world folder different world and robot configurations can be found. Protos folder contains the proto(compact definition) of the robot.
Controller folder in a similar way contains two packages.
1. qre_a1_demo: This is a ros controller for Webots simulator. To run the Webots simulation with ROS follow the steps:
Run Webots and Open the World file
a1_demo_ros.wbt
inside qre_a1_wbsim/worlds folder
webots --mode=pause --batch --stderr --stdout
Play Webots simulation (Ctrl 4) and run the ROS controller
roslaunch qre_wbs_controller wb_controller.launch
For RVIZ visualization run the following command:
roslaunch qre_wbs_controller a1_rviz.launch
The controller will launch a node:
Node [webots_controller]
Publications: wb_joint_states [sensor_msgs/JointState]
Subscriptions: joint_states [sensor_msgs/JointState]
2. qre_wbs_demo: This package contains a bare minimum demo for how
to control the robot using Webots api. The provided code should work out
of the box and user do not need to have any knowledge of Webots api.
Just sending right sequenced joint values and duration in
pose_decomposition
function should work. Similarly here again to run
the world:
Run Webots and Open the World file
a1_demo.wbt
inside qre_a1_wbsim/worlds folder
webots --mode=pause --batch --stderr --stdout