combined some packages
This commit is contained in:
parent
5346d5516a
commit
33918f5dac
36
README.md
36
README.md
|
@ -1,5 +1,5 @@
|
|||
# Introduction
|
||||
Here are the ROS packages of Unitree robots, namely Laikago, Aliengo and A1. You can load robots and joint controllers in Gazebo. And we also offered a basic standing controller and a tool to generate external force. Besides of these simulation functions, you can also control your real robots in ROS by the `unitree_legged_real`.
|
||||
Here are the ROS packages of Unitree robots, namely Laikago, Aliengo and A1. You can load robots and joint controllers in Gazebo. And we also offered a basic standing controller, a position and pose publisher and a tool to generate external force. Besides of these simulation functions, you can also control your real robots in ROS by the `unitree_legged_real`.
|
||||
|
||||
## Packages:
|
||||
Robot description: `a1_description`, `aliengo_description`, `laikago_description`
|
||||
|
@ -8,12 +8,10 @@ Robot and joints controller: `unitree_controller`
|
|||
|
||||
Basic function: `unitree_legged_msgs`
|
||||
|
||||
Simulation related: `unitree_gazebo`, `unitree_worlds`, `unitree_legged_control`
|
||||
Simulation related: `unitree_gazebo`, `unitree_legged_control`
|
||||
|
||||
Real robot control related: `unitree_legged_real`
|
||||
|
||||
Some examples: `unitree_example`
|
||||
|
||||
# Dependencies
|
||||
* [ROS](https://www.ros.org/) melodic or ROS kinetic(has not been tested)
|
||||
* [Gazebo8](http://gazebosim.org/)
|
||||
|
@ -45,10 +43,10 @@ Else if your ROS is kinetic:
|
|||
sudo apt-get install ros-kinetic-controller-manager ros-kinetic-ros-control ros-kinetic-ros-controllers ros-kinetic-joint-state-controller ros-kinetic-effort-controllers ros-kinetic-velocity-controllers ros-kinetic-position-controllers ros-kinetic-robot-controllers ros-kinetic-robot-state-publisher ros-kinetic-gazebo8-ros ros-kinetic-gazebo8-ros-control ros-kinetic-gazebo8-ros-pkgs ros-kinetic-gazebo8-ros-dev
|
||||
```
|
||||
|
||||
And open the file `worlds/stairs.world`. At the end of the file:
|
||||
And open the file `unitree_gazebo/worlds/stairs.world`. At the end of the file:
|
||||
```
|
||||
<include>
|
||||
<uri>model:///home/unitree/catkin_ws/src/unitree/worlds/building_editor_models/stairs</uri>
|
||||
<uri>model:///home/unitree/catkin_ws/src/unitree_ros/unitree_gazebo/worlds/building_editor_models/stairs</uri>
|
||||
</include>
|
||||
```
|
||||
Please change the path of `building_editor_models/stairs` to the real path on your PC.
|
||||
|
@ -82,7 +80,8 @@ 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`. 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.
|
||||
|
||||
Then you can start to control the robot:
|
||||
### Stand controller
|
||||
After launching the gazebo simulation, you can start to control the robot:
|
||||
```
|
||||
rosrun unitree_controller unitree_servo
|
||||
```
|
||||
|
@ -91,6 +90,15 @@ 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.
|
||||
|
||||
## unitree_legged_real
|
||||
You can control your real robot(only A1 and Aliengo) from ROS by this package.
|
||||
|
||||
|
@ -113,17 +121,3 @@ torque_lcm
|
|||
The `velocity_lcm` and `torque_lcm` have to run under root account too. Please use the same method as runing `real_launch`.
|
||||
|
||||
And when you run the high level controller, please make sure the robot is standing on the ground. The high level only has `walk_lcm`.
|
||||
|
||||
## unitree_examples:
|
||||
### laikago_move:
|
||||
In this package, we showed how to control the position and pose of robot without a controller, which should be useful in SLAM or visual development.
|
||||
|
||||
First launch a gazobe simulation of Laikago:
|
||||
```
|
||||
roslaunch unitree_gazebo normal.launch
|
||||
```
|
||||
Then run the position and pose publisher in another terminal:
|
||||
```
|
||||
rosrun unitree_examples laikago_move
|
||||
```
|
||||
The Laikago will turn around the origin.
|
|
@ -1,21 +0,0 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_examples)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
std_msgs
|
||||
)
|
||||
|
||||
find_package(gazebo REQUIRED)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
)
|
||||
|
||||
include_directories(
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${GAZEBO_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
add_executable(laikago_move src/move_publisher.cpp)
|
||||
target_link_libraries(laikago_move ${catkin_LIBRARIES})
|
|
@ -1,42 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="paused" default="true"/>
|
||||
<arg name="use_sim_time" default="true"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="debug" default="false"/>
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<arg name="user_debug" default="false"/>
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(find unitree_worlds)/earth.world"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
</include>
|
||||
|
||||
<!-- Load the URDF into the ROS Parameter Server -->
|
||||
<param name="robot_description"
|
||||
command="$(find xacro)/xacro --inorder '$(find laikago_description)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug)"/>
|
||||
|
||||
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
|
||||
<!-- Set trunk and joint positions at startup -->
|
||||
<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner" respawn="false" output="screen"
|
||||
args="-urdf -z 0.6 -model laikago_gazebo -param robot_description -unpause"/>
|
||||
|
||||
<!-- Load joint controller configurations from YAML file to parameter server -->
|
||||
<rosparam file="$(find laikago_description)/config/robot_control.yaml" command="load"/>
|
||||
|
||||
<!-- load the controllers -->
|
||||
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
|
||||
output="screen" ns="/laikago_gazebo" args="joint_state_controller
|
||||
FL_hip_controller FL_thigh_controller FL_calf_controller
|
||||
FR_hip_controller FR_thigh_controller FR_calf_controller
|
||||
RL_hip_controller RL_thigh_controller RL_calf_controller
|
||||
RR_hip_controller RR_thigh_controller RR_calf_controller "/>
|
||||
|
||||
|
||||
</launch>
|
|
@ -1,19 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_examples</name>
|
||||
<version>0.0.1</version>
|
||||
<description>The examples package</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
|
||||
</package>
|
|
@ -1,54 +0,0 @@
|
|||
#include <ros/ros.h>
|
||||
#include <gazebo_msgs/ModelState.h>
|
||||
#include <gazebo_msgs/SetModelState.h>
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
#include <tf/transform_datatypes.h>
|
||||
// #include <std_msgs/Float64.h>
|
||||
#include <math.h>
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "move_publisher");
|
||||
ros::NodeHandle nh;
|
||||
ros::Publisher move_publisher = nh.advertise<gazebo_msgs::ModelState>("/gazebo/set_model_state", 1000);
|
||||
|
||||
gazebo_msgs::ModelState model_state_pub;
|
||||
|
||||
model_state_pub.model_name = "laikago_gazebo";
|
||||
model_state_pub.pose.position.x = 0.0;
|
||||
model_state_pub.pose.position.y = 0.0;
|
||||
model_state_pub.pose.position.z = 0.5;
|
||||
|
||||
model_state_pub.pose.orientation.x = 0.0;
|
||||
model_state_pub.pose.orientation.y = 0.0;
|
||||
model_state_pub.pose.orientation.z = 0.0;
|
||||
model_state_pub.pose.orientation.w = 1.0;
|
||||
|
||||
// model_state_pub.twist.linear.x= 0.02; //0.02: 2cm/sec
|
||||
// model_state_pub.twist.linear.y= 0.0;
|
||||
// model_state_pub.twist.linear.z= 0.08;
|
||||
|
||||
// model_state_pub.twist.angular.x= 0.0;
|
||||
// model_state_pub.twist.angular.y= 0.0;
|
||||
// model_state_pub.twist.angular.z= 0.0;
|
||||
|
||||
model_state_pub.reference_frame = "world";
|
||||
// model_state_pub.reference_frame = "base";
|
||||
|
||||
long long time_ms = 0; //time, ms
|
||||
const double period = 5000; //ms
|
||||
const double radius = 1.5; //m
|
||||
tf::Quaternion q;
|
||||
ros::Rate loop_rate(1000);
|
||||
while(ros::ok())
|
||||
{
|
||||
model_state_pub.pose.position.x = radius * sin(2*M_PI*(double)time_ms/period);
|
||||
model_state_pub.pose.position.y = radius * cos(2*M_PI*(double)time_ms/period);
|
||||
model_state_pub.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, - 2*M_PI*(double)time_ms/period);
|
||||
|
||||
move_publisher.publish(model_state_pub);
|
||||
loop_rate.sleep();
|
||||
time_ms += 1;
|
||||
}
|
||||
}
|
|
@ -54,4 +54,5 @@ target_link_libraries(unitree_external_force ${catkin_LIBRARIES})
|
|||
add_executable(unitree_servo src/servo.cpp)
|
||||
target_link_libraries(unitree_servo ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
|
||||
|
||||
add_executable(unitree_move_kinetic src/move_publisher.cpp)
|
||||
target_link_libraries(unitree_move_kinetic ${catkin_LIBRARIES})
|
|
@ -0,0 +1,80 @@
|
|||
#include <ros/ros.h>
|
||||
#include <gazebo_msgs/ModelState.h>
|
||||
#include <gazebo_msgs/SetModelState.h>
|
||||
#include <string>
|
||||
#include <stdio.h>
|
||||
#include <tf/transform_datatypes.h>
|
||||
// #include <std_msgs/Float64.h>
|
||||
#include <math.h>
|
||||
#include <iostream>
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
enum coord
|
||||
{
|
||||
WORLD,
|
||||
ROBOT
|
||||
};
|
||||
coord def_frame = coord::WORLD;
|
||||
|
||||
ros::init(argc, argv, "move_publisher");
|
||||
ros::NodeHandle nh;
|
||||
ros::Publisher move_publisher = nh.advertise<gazebo_msgs::ModelState>("/gazebo/set_model_state", 1000);
|
||||
|
||||
gazebo_msgs::ModelState model_state_pub;
|
||||
|
||||
std::string robot_name;
|
||||
ros::param::get("/robot_name", robot_name);
|
||||
std::cout << "robot_name: " << robot_name << std::endl;
|
||||
|
||||
model_state_pub.model_name = robot_name + "_gazebo";
|
||||
ros::Rate loop_rate(1000);
|
||||
|
||||
if(def_frame == coord::WORLD)
|
||||
{
|
||||
model_state_pub.pose.position.x = 0.0;
|
||||
model_state_pub.pose.position.y = 0.0;
|
||||
model_state_pub.pose.position.z = 0.5;
|
||||
|
||||
model_state_pub.pose.orientation.x = 0.0;
|
||||
model_state_pub.pose.orientation.y = 0.0;
|
||||
model_state_pub.pose.orientation.z = 0.0;
|
||||
model_state_pub.pose.orientation.w = 1.0;
|
||||
|
||||
model_state_pub.reference_frame = "world";
|
||||
|
||||
long long time_ms = 0; //time, ms
|
||||
const double period = 5000; //ms
|
||||
const double radius = 1.5; //m
|
||||
tf::Quaternion q;
|
||||
while(ros::ok())
|
||||
{
|
||||
model_state_pub.pose.position.x = radius * sin(2*M_PI*(double)time_ms/period);
|
||||
model_state_pub.pose.position.y = radius * cos(2*M_PI*(double)time_ms/period);
|
||||
model_state_pub.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, - 2*M_PI*(double)time_ms/period);
|
||||
|
||||
move_publisher.publish(model_state_pub);
|
||||
loop_rate.sleep();
|
||||
time_ms += 1;
|
||||
}
|
||||
}
|
||||
else if(def_frame == coord::ROBOT)
|
||||
{
|
||||
model_state_pub.twist.linear.x= 0.02; //0.02: 2cm/sec
|
||||
model_state_pub.twist.linear.y= 0.0;
|
||||
model_state_pub.twist.linear.z= 0.08;
|
||||
|
||||
model_state_pub.twist.angular.x= 0.0;
|
||||
model_state_pub.twist.angular.y= 0.0;
|
||||
model_state_pub.twist.angular.z= 0.0;
|
||||
|
||||
model_state_pub.reference_frame = "base";
|
||||
|
||||
while(ros::ok())
|
||||
{
|
||||
move_publisher.publish(model_state_pub);
|
||||
loop_rate.sleep();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
|
@ -13,7 +13,7 @@
|
|||
<arg name="user_debug" default="false"/>
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(find unitree_worlds)/$(arg wname).world"/>
|
||||
<arg name="world_name" value="$(find unitree_gazebo)/worlds/$(arg wname).world"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
|
|
|
@ -109,7 +109,7 @@
|
|||
</model>
|
||||
|
||||
<include>
|
||||
<uri>model:///home/bian/catkin_ws/src/unitree/worlds/building_editor_models/stairs</uri>
|
||||
<uri>model:///home/bian/catkin_ws/src/unitree_ros/unitree_gazebo/worlds/building_editor_models/stairs</uri>
|
||||
</include>
|
||||
|
||||
</world>
|
|
@ -28,4 +28,5 @@ link_directories($(catkin_LIB_DIRS) lib)
|
|||
add_library( unitree_legged_control
|
||||
src/joint_controller.cpp
|
||||
)
|
||||
add_dependencies(${PROJECT_NAME} unitree_legged_msgs_gencpp)
|
||||
target_link_libraries(unitree_legged_control ${catkin_LIBRARIES} unitree_joint_control_tool)
|
||||
|
|
|
@ -45,4 +45,4 @@ install(
|
|||
DIRECTORY include/${PROJECT_NAME}/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
FILES_MATCHING PATTERN "*.h"
|
||||
)
|
||||
)
|
|
@ -1,4 +0,0 @@
|
|||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(unitree_ros)
|
||||
find_package(catkin REQUIRED)
|
||||
catkin_metapackage()
|
|
@ -1,14 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_ros</name>
|
||||
<version>0.0.1</version>
|
||||
<description>This is the metapackage of all unitree robots</description>
|
||||
<maintainer email="unitree@todo.todo">TODO</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<export>
|
||||
<metapackage />
|
||||
</export>
|
||||
</package>
|
|
@ -1,14 +0,0 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_worlds)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
)
|
|
@ -1,12 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_worlds</name>
|
||||
<version>0.0.1</version>
|
||||
<description>The worlds package</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
</package>
|
Loading…
Reference in New Issue