unitree ros packages
This commit is contained in:
commit
5346d5516a
|
@ -0,0 +1,129 @@
|
|||
# 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`.
|
||||
|
||||
## Packages:
|
||||
Robot description: `a1_description`, `aliengo_description`, `laikago_description`
|
||||
|
||||
Robot and joints controller: `unitree_controller`
|
||||
|
||||
Basic function: `unitree_legged_msgs`
|
||||
|
||||
Simulation related: `unitree_gazebo`, `unitree_worlds`, `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/)
|
||||
* [unitree_legged_sdk](https://github.com/unitreerobotics)
|
||||
|
||||
# Configuration
|
||||
Make sure the following exist in your `~/.bashrc` file or export them in terminal. `melodic`, `gazebo-8`, `~/catkin_ws`, `amd64` and the paths to `unitree_legged_sdk` should be replaced in your own case.
|
||||
```
|
||||
source /opt/ros/melodic/setup.bash
|
||||
source /usr/share/gazebo-8/setup.sh
|
||||
source ~/catkin_ws/devel/setup.bash
|
||||
export ROS_PACKAGE_PATH=~/catkin_ws:${ROS_PACKAGE_PATH}
|
||||
export GAZEBO_PLUGIN_PATH=~/catkin_ws/devel/lib:${GAZEBO_PLUGIN_PATH}
|
||||
export LD_LIBRARY_PATH=~/catkin_ws/devel/lib:${LD_LIBRARY_PATH}
|
||||
export UNITREE_LEGGED_SDK_PATH=~/unitree_legged_sdk
|
||||
#amd64, arm32, arm64
|
||||
export UNITREE_PLATFORM="amd64"
|
||||
```
|
||||
|
||||
# Build
|
||||
Please run the following command to install relative packages.
|
||||
|
||||
If your ROS is melodic:
|
||||
```
|
||||
sudo apt-get install ros-melodic-controller-interface ros-melodic-gazebo-ros-control ros-melodic-joint-state-controller ros-melodic-effort-controllers ros-melodic-joint-trajectory-controller
|
||||
```
|
||||
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:
|
||||
```
|
||||
<include>
|
||||
<uri>model:///home/unitree/catkin_ws/src/unitree/worlds/building_editor_models/stairs</uri>
|
||||
</include>
|
||||
```
|
||||
Please change the path of `building_editor_models/stairs` to the real path on your PC.
|
||||
|
||||
Then you can use catkin_make to build:
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
catkin_make
|
||||
```
|
||||
|
||||
If you face a dependency problem, you can just run `catkin_make` again.
|
||||
|
||||
# Detail of Packages
|
||||
## unitree_legged_control:
|
||||
It contains the joints controllers for Gazebo simulation, which allows user to control joints with position, velocity and torque.
|
||||
|
||||
## unitree_legged_msgs:
|
||||
ros-type message, including command and state of high-level and low-level control.
|
||||
It would be better if it be compiled firstly, otherwise you may have dependency problems (such as that you can't find the header file).
|
||||
|
||||
## The description of robots:
|
||||
Namely the description of A1, Aliengo and Laikago. Each package include mesh, urdf and xacro files of robot. Take Laikago as an example, you can check the model in Rviz by:
|
||||
```
|
||||
roslaunch laikago_description laikago_rviz.launch
|
||||
```
|
||||
|
||||
## 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`. 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:
|
||||
```
|
||||
rosrun unitree_controller unitree_servo
|
||||
```
|
||||
|
||||
And you can add external disturbances, like a push or a kick:
|
||||
```
|
||||
rosrun unitree_controller unitree_external_force
|
||||
```
|
||||
## unitree_legged_real
|
||||
You can control your real robot(only A1 and Aliengo) from ROS by this package.
|
||||
|
||||
First you have to run the `real_launch` under root account:
|
||||
```
|
||||
sudo su
|
||||
source ~/catkin_ws/devel/setup.bash
|
||||
roslaunch unitree_legged_real real.launch rname:=a1 ctrl_level:=lowlevel
|
||||
```
|
||||
These commands will launch a LCM server. The `rname` means robot name, which can be `a1` or `aliengo`(case does not matter), and the default value is `a1`. And the `ctrl_level` means the control level, which can be `lowlevel` or `higelevel`(case does not matter), and the default value is `higelevel`. Under the low level, you can control the joints directly. And under the high level, you can control the robot to move or change its pose. To do so, you need to run the controller in another terminal:
|
||||
```
|
||||
rosrun unitree_legged_real position_lcm
|
||||
```
|
||||
We offered some examples. When you run the low level controller, please make sure the robot is hanging up. The low level contains:
|
||||
```
|
||||
position_lcm
|
||||
velocity_lcm
|
||||
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.
|
|
@ -0,0 +1,21 @@
|
|||
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})
|
|
@ -0,0 +1,42 @@
|
|||
<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>
|
|
@ -0,0 +1,19 @@
|
|||
<?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>
|
|
@ -0,0 +1,54 @@
|
|||
#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;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,19 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(a1_description)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
genmsg
|
||||
roscpp
|
||||
std_msgs
|
||||
tf
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
)
|
||||
|
||||
include_directories(
|
||||
# include
|
||||
${Boost_INCLUDE_DIR}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
|
@ -0,0 +1,70 @@
|
|||
a1_gazebo:
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 1000
|
||||
|
||||
# FL Controllers ---------------------------------------
|
||||
FL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# FR Controllers ---------------------------------------
|
||||
FR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RL Controllers ---------------------------------------
|
||||
RL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RR Controllers ---------------------------------------
|
||||
RR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
|
@ -0,0 +1,23 @@
|
|||
<launch>
|
||||
|
||||
<arg name="user_debug" default="false"/>
|
||||
|
||||
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find a1_description)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug)"/>
|
||||
|
||||
<!-- for higher robot_state_publisher average rate-->
|
||||
<!-- <param name="rate" value="1000"/> -->
|
||||
|
||||
<!-- send fake joint values -->
|
||||
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher">
|
||||
<param name="use_gui" value="TRUE"/>
|
||||
</node>
|
||||
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
|
||||
<param name="publish_frequency" type="double" value="1000.0"/>
|
||||
</node>
|
||||
|
||||
<node pkg="rviz" type="rviz" name="rviz" respawn="false" output="screen"
|
||||
args="-d $(find a1_description)/launch/check_joint.rviz"/>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,265 @@
|
|||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /RobotModel1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 420
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
FL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
RL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
trunk:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/Axes
|
||||
Enabled: false
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: false
|
||||
- Class: rviz/TF
|
||||
Enabled: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: false
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 238; 238; 238
|
||||
Default Light: true
|
||||
Fixed Frame: base
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Topic: /initialpose
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 1.0307118892669678
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0.0760490670800209
|
||||
Y: 0.11421932280063629
|
||||
Z: -0.1576911211013794
|
||||
Focal Shape Fixed Size: false
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 1.0047969818115234
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 4.558584690093994
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 627
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000022ffc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000270000022f000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d0065000000000000000640000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002e40000022f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1108
|
||||
X: 812
|
||||
Y: 241
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 70 KiB |
|
@ -0,0 +1,14 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>a1_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The a1_description package</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<depend>roscpp</depend>
|
||||
<depend>std_msgs</depend>
|
||||
|
||||
</package>
|
|
@ -0,0 +1,701 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="a1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.267 0.194 0.114"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.012731 0.002186 0.000515"/>
|
||||
<mass value="4.713"/>
|
||||
<inertia ixx="0.01683993" ixy="8.3902e-05" ixz="0.000597679" iyy="0.056579028" iyz="2.5134e-05" izz="0.064713601"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.183 -0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003311 -0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08505 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FR_calf"/>
|
||||
<child link="FR_foot"/>
|
||||
</joint>
|
||||
<link name="FR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.183 0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003311 0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.08505 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FL_calf"/>
|
||||
<child link="FL_foot"/>
|
||||
</joint>
|
||||
<link name="FL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.183 -0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.003311 -0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08505 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RR_calf"/>
|
||||
<child link="RR_foot"/>
|
||||
</joint>
|
||||
<link name="RR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.183 0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.003311 0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.08505 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RL_calf"/>
|
||||
<child link="RL_foot"/>
|
||||
</joint>
|
||||
<link name="RL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</robot>
|
||||
|
|
@ -0,0 +1,104 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="a1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- Constants for robot dimensions -->
|
||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||
<xacro:property name="stick_mass" value="0.00001"/>
|
||||
|
||||
<!-- simplified collision value -->
|
||||
<xacro:property name="trunk_width" value="0.194"/>
|
||||
<xacro:property name="trunk_length" value="0.267"/>
|
||||
<xacro:property name="trunk_height" value="0.114"/>
|
||||
<xacro:property name="hip_radius" value="0.046"/>
|
||||
<xacro:property name="hip_length" value="0.04"/>
|
||||
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
|
||||
<xacro:property name="thigh_shoulder_length" value="0.032"/>
|
||||
<xacro:property name="thigh_width" value="0.0245"/>
|
||||
<xacro:property name="thigh_height" value="0.034"/>
|
||||
<xacro:property name="calf_width" value="0.016"/>
|
||||
<xacro:property name="calf_height" value="0.016"/>
|
||||
<xacro:property name="foot_radius" value="0.02"/>
|
||||
<xacro:property name="stick_radius" value="0.01"/>
|
||||
<xacro:property name="stick_length" value="0.2"/>
|
||||
|
||||
<!-- kinematic value -->
|
||||
<xacro:property name="thigh_offset" value="0.08505"/>
|
||||
<xacro:property name="thigh_length" value="0.2"/>
|
||||
<xacro:property name="calf_length" value="0.2"/>
|
||||
|
||||
<!-- leg offset from trunk center value -->
|
||||
<xacro:property name="leg_offset_x" value="0.183"/>
|
||||
<xacro:property name="leg_offset_y" value="0.047"/>
|
||||
<xacro:property name="trunk_offset_z" value="0.01675"/>
|
||||
<xacro:property name="hip_offset" value="0.065"/>
|
||||
|
||||
<!-- joint limits -->
|
||||
<xacro:property name="damping" value="0"/>
|
||||
<xacro:property name="friction" value="0"/>
|
||||
<xacro:property name="hip_max" value="46"/>
|
||||
<xacro:property name="hip_min" value="-46"/>
|
||||
<xacro:property name="hip_velocity_max" value="52.4"/>
|
||||
<xacro:property name="hip_torque_max" value="20"/>
|
||||
<xacro:property name="thigh_max" value="240"/>
|
||||
<xacro:property name="thigh_min" value="-60"/>
|
||||
<xacro:property name="thigh_velocity_max" value="28.6"/>
|
||||
<xacro:property name="thigh_torque_max" value="55"/>
|
||||
<xacro:property name="calf_max" value="-52.5"/>
|
||||
<xacro:property name="calf_min" value="-154.5"/>
|
||||
<xacro:property name="calf_velocity_max" value="28.6"/>
|
||||
<xacro:property name="calf_torque_max" value="55"/>
|
||||
|
||||
<!-- dynamics inertial value -->
|
||||
<!-- trunk -->
|
||||
<xacro:property name="trunk_mass" value="4.713"/>
|
||||
<xacro:property name="trunk_com_x" value="0.012731"/>
|
||||
<xacro:property name="trunk_com_y" value="0.002186"/>
|
||||
<xacro:property name="trunk_com_z" value="0.000515"/>
|
||||
<xacro:property name="trunk_ixx" value="0.016839930"/>
|
||||
<xacro:property name="trunk_ixy" value="0.000083902"/>
|
||||
<xacro:property name="trunk_ixz" value="0.000597679"/>
|
||||
<xacro:property name="trunk_iyy" value="0.056579028"/>
|
||||
<xacro:property name="trunk_iyz" value="0.000025134"/>
|
||||
<xacro:property name="trunk_izz" value="0.064713601"/>
|
||||
|
||||
<!-- hip (left front) -->
|
||||
<xacro:property name="hip_mass" value="0.696"/>
|
||||
<xacro:property name="hip_com_x" value="-0.003311"/>
|
||||
<xacro:property name="hip_com_y" value="0.000635"/>
|
||||
<xacro:property name="hip_com_z" value="0.000031"/>
|
||||
<xacro:property name="hip_ixx" value="0.000469246"/>
|
||||
<xacro:property name="hip_ixy" value="-0.000009409"/>
|
||||
<xacro:property name="hip_ixz" value="-0.000000342"/>
|
||||
<xacro:property name="hip_iyy" value="0.000807490"/>
|
||||
<xacro:property name="hip_iyz" value="-0.000000466"/>
|
||||
<xacro:property name="hip_izz" value="0.000552929"/>
|
||||
|
||||
<!-- thigh -->
|
||||
<xacro:property name="thigh_mass" value="1.013"/>
|
||||
<xacro:property name="thigh_com_x" value="-0.003237"/>
|
||||
<xacro:property name="thigh_com_y" value="-0.022327"/>
|
||||
<xacro:property name="thigh_com_z" value="-0.027326"/>
|
||||
<xacro:property name="thigh_ixx" value="0.005529065"/>
|
||||
<xacro:property name="thigh_ixy" value="0.000004825"/>
|
||||
<xacro:property name="thigh_ixz" value="0.000343869"/>
|
||||
<xacro:property name="thigh_iyy" value="0.005139339"/>
|
||||
<xacro:property name="thigh_iyz" value="0.000022448"/>
|
||||
<xacro:property name="thigh_izz" value="0.001367788"/>
|
||||
|
||||
<!-- calf -->
|
||||
<xacro:property name="calf_mass" value="0.166"/>
|
||||
<xacro:property name="calf_com_x" value="0.006435"/>
|
||||
<xacro:property name="calf_com_y" value="0.0"/>
|
||||
<xacro:property name="calf_com_z" value="-0.107388"/>
|
||||
<xacro:property name="calf_ixx" value="0.002997972"/>
|
||||
<xacro:property name="calf_ixy" value="0.0"/>
|
||||
<xacro:property name="calf_ixz" value="-0.000141163"/>
|
||||
<xacro:property name="calf_iyy" value="0.003014022"/>
|
||||
<xacro:property name="calf_iyz" value="0.0"/>
|
||||
<xacro:property name="calf_izz" value="0.000032426"/>
|
||||
|
||||
<!-- foot -->
|
||||
<xacro:property name="foot_mass" value="0.06"/>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,266 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/a1_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of trunk center. -->
|
||||
<gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>10</frequency>
|
||||
<plot>
|
||||
<link>base</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
|
||||
<!-- <gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>100</frequency>
|
||||
<plot>
|
||||
<link>FL_foot</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Green</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
|
||||
<bodyName>trunk</bodyName>
|
||||
<topicName>/apply_force/trunk</topicName>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>trunk_imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>1000.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Foot contacts. -->
|
||||
<gazebo reference="FR_calf">
|
||||
<sensor name="FR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<sensor name="FL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<sensor name="RR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<sensor name="RL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Visualization of Foot contacts. -->
|
||||
<gazebo reference="FR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="base">
|
||||
<material>Gazebo/Green</material>
|
||||
<turnGravityOff>false</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="stick_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/White</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- FL leg -->
|
||||
<gazebo reference="FL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- FR leg -->
|
||||
<gazebo reference="FR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RL leg -->
|
||||
<gazebo reference="RL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RR leg -->
|
||||
<gazebo reference="RR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,176 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find a1_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae *origin">
|
||||
|
||||
<joint name="${name}_hip_joint" type="revolute">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<xacro:if value="${(mirror_dae == True)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_min*PI/180.0}" upper="${hip_max*PI/180.0}"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_max*PI/180.0}" upper="${-hip_min*PI/180.0}"/>
|
||||
</xacro:if>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_hip">
|
||||
<visual>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||
<mass value="${hip_mass}"/>
|
||||
<inertia
|
||||
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||
izz="${hip_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint>
|
||||
|
||||
<!-- this link is only for collision -->
|
||||
<link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_min*PI/180.0}" upper="${thigh_max*PI/180.0}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<xacro:if value="${mirror_dae == True}">
|
||||
<mesh filename="package://a1_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${mirror_dae == False}">
|
||||
<mesh filename="package://a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||
<mass value="${thigh_mass}"/>
|
||||
<inertia
|
||||
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||
izz="${thigh_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
<child link="${name}_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_min*PI/180.0}" upper="${calf_max*PI/180.0}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||
<mass value="${calf_mass}"/>
|
||||
<inertia
|
||||
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||
izz="${calf_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||
<parent link="${name}_calf"/>
|
||||
<child link="${name}_foot"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius-0.01}"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${foot_mass}"/>
|
||||
<inertia
|
||||
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:leg_transmission name="${name}"/>
|
||||
</xacro:macro>
|
||||
</robot>
|
|
@ -0,0 +1,40 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="silver">
|
||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="orange">
|
||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="brown">
|
||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,142 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="a1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find a1_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/leg.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/stairs.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/gazebo.xacro"/>
|
||||
<!-- <xacro:include filename="$(find a1_gazebo)/launch/stairs.urdf.xacro"/> -->
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
||||
|
||||
<!-- Rollover Protection mode will add an additional stick on the top, use "true" or "false" to switch it. -->
|
||||
<xacro:property name="rolloverProtection" value="false"/>
|
||||
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
||||
<mass value="${trunk_mass}"/>
|
||||
<inertia
|
||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||
izz="${trunk_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${(rolloverProtection == 'true')}">
|
||||
<joint name="stick_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="stick_link"/>
|
||||
<origin rpy="0 0 0" xyz="${0.18} 0 ${stick_length/2.0+0.08}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stick_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${stick_mass}"/>
|
||||
<inertia
|
||||
ixx="${stick_mass / 2.0 * (stick_radius*stick_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}" iyz="0.0"
|
||||
izz="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae="False" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,46 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:property name="stair_length" value="0.640" />
|
||||
<xacro:property name="stair_width" value="0.310" />
|
||||
<xacro:property name="stair_height" value="0.170" />
|
||||
|
||||
<xacro:macro name="stairs" params="stairs xpos ypos zpos">
|
||||
|
||||
<joint name="stair_joint_origin" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="stair_link_${stairs}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stair_link_${stairs}">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
<origin rpy="0 0 0" xyz="${xpos} ${ypos} ${zpos}"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.80"/>
|
||||
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${stairs}">
|
||||
<xacro:stairs stairs="${stairs-1}" xpos="0" ypos="${ypos-stair_width/2}" zpos="${zpos+stair_height}"/>
|
||||
<joint name="stair_joint_${stairs}" type="fixed">
|
||||
<parent link="stair_link_${stairs}"/>
|
||||
<child link="stair_link_${stairs-1}"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,42 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="leg_transmission" params="name">
|
||||
|
||||
<transmission name="${name}_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,19 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(aliengo_description)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
genmsg
|
||||
roscpp
|
||||
std_msgs
|
||||
tf
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
)
|
||||
|
||||
include_directories(
|
||||
# include
|
||||
${Boost_INCLUDE_DIR}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
|
@ -0,0 +1,70 @@
|
|||
aliengo_gazebo:
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 1000
|
||||
|
||||
# FL Controllers ---------------------------------------
|
||||
FL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# FR Controllers ---------------------------------------
|
||||
FR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RL Controllers ---------------------------------------
|
||||
RL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RR Controllers ---------------------------------------
|
||||
RR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
|
@ -0,0 +1,23 @@
|
|||
<launch>
|
||||
|
||||
<arg name="user_debug" default="false"/>
|
||||
|
||||
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find aliengo_description)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug)"/>
|
||||
|
||||
<!-- for higher robot_state_publisher average rate-->
|
||||
<!-- <param name="rate" value="1000"/> -->
|
||||
|
||||
<!-- send fake joint values -->
|
||||
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher">
|
||||
<param name="use_gui" value="TRUE"/>
|
||||
</node>
|
||||
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
|
||||
<param name="publish_frequency" type="double" value="1000.0"/>
|
||||
</node>
|
||||
|
||||
<node pkg="rviz" type="rviz" name="rviz" respawn="false" output="screen"
|
||||
args="-d $(find aliengo_description)/launch/check_joint.rviz"/>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,244 @@
|
|||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 420
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
FL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
RL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
trunk:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/Axes
|
||||
Enabled: false
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.10000000149011612
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: false
|
||||
- Class: rviz/TF
|
||||
Enabled: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: false
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 238; 238; 238
|
||||
Default Light: true
|
||||
Fixed Frame: base
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Topic: /initialpose
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 1.4732182025909424
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0.0760490670800209
|
||||
Y: 0.11421932280063629
|
||||
Z: -0.1576911211013794
|
||||
Focal Shape Fixed Size: false
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.49979713559150696
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 5.093583106994629
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 627
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000022ffc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000270000022f000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d0065000000000000000640000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002e40000022f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1108
|
||||
X: 812
|
||||
Y: 241
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 130 KiB |
|
@ -0,0 +1,14 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>aliengo_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The aliengo_description package</description>
|
||||
|
||||
<maintainer email="aliengo@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<depend>roscpp</depend>
|
||||
<depend>std_msgs</depend>
|
||||
|
||||
</package>
|
|
@ -0,0 +1,718 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="aliengo_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
<!-- <xacro:include filename="$(find aliengo_gazebo)/launch/gazebo.xacro"/> -->
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<!-- <xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if> -->
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.647 0.15 0.112"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- <collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.008465 0.004045 -0.000763"/>
|
||||
<mass value="9.041"/>
|
||||
<inertia ixx="0.033260231" ixy="-0.000451628" ixz="0.000487603" iyy="0.16117211" iyz="4.8356e-05" izz="0.17460442"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.2399 -0.051 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.083 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0418" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.022191 -0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="7.185e-05" ixz="-1.262e-06" iyy="0.004907517" iyz="1.75e-06" izz="0.005586944"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="FR_thigh_joint" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 -0.083 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" velocity="20"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0374 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="-3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="-1.0086e-05" izz="0.000369811"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0208 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FR_calf"/>
|
||||
<child link="FR_foot"/>
|
||||
</joint>
|
||||
<link name="FR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.2399 0.051 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.083 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0418" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.022191 0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="-7.185e-05" ixz="-1.262e-06" iyy="0.004907517" iyz="-1.75e-06" izz="0.005586944"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="FL_thigh_joint" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 0.083 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" velocity="20"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0374 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 -0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="1.0086e-05" izz="0.000369811"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0208 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FL_calf"/>
|
||||
<child link="FL_foot"/>
|
||||
</joint>
|
||||
<link name="FL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.2399 -0.051 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.083 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0418" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.022191 -0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="-7.185e-05" ixz="1.262e-06" iyy="0.004907517" iyz="1.75e-06" izz="0.005586944"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="RR_thigh_joint" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 -0.083 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" velocity="20"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0374 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="-3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="-1.0086e-05" izz="0.000369811"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0208 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RR_calf"/>
|
||||
<child link="RR_foot"/>
|
||||
</joint>
|
||||
<link name="RR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.2399 0.051 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.083 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0418" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.022191 0.015144 -1.5e-05"/>
|
||||
<mass value="1.993"/>
|
||||
<inertia ixx="0.002903894" ixy="7.185e-05" ixz="1.262e-06" iyy="0.004907517" iyz="-1.75e-06" izz="0.005586944"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
<joint name="RL_thigh_joint" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 0.083 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="44" velocity="20"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0374 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.005607 -0.003877 -0.048199"/>
|
||||
<mass value="0.639"/>
|
||||
<inertia ixx="0.005666803" ixy="3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="1.0086e-05" izz="0.000369811"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.0208 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
|
||||
<mass value="0.207"/>
|
||||
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RL_calf"/>
|
||||
<child link="RL_foot"/>
|
||||
</joint>
|
||||
<link name="RL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||
</robot>
|
||||
|
|
@ -0,0 +1,102 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="aliengo_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- Constants for robot dimensions -->
|
||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||
<xacro:property name="stick_mass" value="0.00001"/>
|
||||
|
||||
<!-- simplified collision value -->
|
||||
<xacro:property name="trunk_width" value="0.150"/>
|
||||
<xacro:property name="trunk_length" value="0.647"/>
|
||||
<xacro:property name="trunk_height" value="0.112"/>
|
||||
<xacro:property name="hip_radius" value="0.046"/>
|
||||
<xacro:property name="hip_length" value="0.0418"/>
|
||||
<xacro:property name="thigh_shoulder_radius" value="0.044"/>
|
||||
<xacro:property name="thigh_shoulder_length" value="0.08"/>
|
||||
<xacro:property name="thigh_width" value="0.0374"/>
|
||||
<xacro:property name="thigh_height" value="0.043"/>
|
||||
<xacro:property name="calf_width" value="0.0208"/>
|
||||
<xacro:property name="calf_height" value="0.016"/>
|
||||
<xacro:property name="foot_radius" value="0.0265"/>
|
||||
<xacro:property name="stick_radius" value="0.01"/>
|
||||
<xacro:property name="stick_length" value="0.2"/>
|
||||
|
||||
<!-- kinematic value -->
|
||||
<xacro:property name="thigh_offset" value="0.083"/>
|
||||
<xacro:property name="thigh_length" value="0.25"/>
|
||||
<xacro:property name="calf_length" value="0.25"/>
|
||||
|
||||
<!-- leg offset from trunk center value -->
|
||||
<xacro:property name="leg_offset_x" value="0.2399"/>
|
||||
<xacro:property name="leg_offset_y" value="0.051"/>
|
||||
<xacro:property name="trunk_offset_z" value="0.01675"/>
|
||||
<xacro:property name="hip_offset" value="0.083"/>
|
||||
|
||||
<!-- joint limits -->
|
||||
<xacro:property name="damping" value="0"/>
|
||||
<xacro:property name="friction" value="0"/>
|
||||
<xacro:property name="hip_position_max" value="${70*PI/180.0}"/>
|
||||
<xacro:property name="hip_position_min" value="${-70*PI/180.0}"/>
|
||||
<xacro:property name="hip_velocity_max" value="20"/>
|
||||
<xacro:property name="hip_torque_max" value="44"/>
|
||||
<xacro:property name="thigh_velocity_max" value="20"/>
|
||||
<xacro:property name="thigh_torque_max" value="44"/>
|
||||
<xacro:property name="calf_position_max" value="${-37*PI/180.0}"/>
|
||||
<xacro:property name="calf_position_min" value="${-159*PI/180.0}"/>
|
||||
<xacro:property name="calf_velocity_max" value="16"/>
|
||||
<xacro:property name="calf_torque_max" value="55"/>
|
||||
|
||||
<!-- dynamics inertial value -->
|
||||
<!-- trunk -->
|
||||
<xacro:property name="trunk_mass" value="9.041"/>
|
||||
<xacro:property name="trunk_com_x" value="0.008465"/>
|
||||
<xacro:property name="trunk_com_y" value="0.004045"/>
|
||||
<xacro:property name="trunk_com_z" value="-0.000763"/>
|
||||
<xacro:property name="trunk_ixx" value="0.033260231"/>
|
||||
<xacro:property name="trunk_ixy" value="-0.000451628"/>
|
||||
<xacro:property name="trunk_ixz" value="0.000487603"/>
|
||||
<xacro:property name="trunk_iyy" value="0.16117211"/>
|
||||
<xacro:property name="trunk_iyz" value="0.000048356"/>
|
||||
<xacro:property name="trunk_izz" value="0.17460442"/>
|
||||
|
||||
<!-- hip (left front) -->
|
||||
<xacro:property name="hip_mass" value="1.993"/>
|
||||
<xacro:property name="hip_com_x" value="-0.022191"/>
|
||||
<xacro:property name="hip_com_y" value="0.015144"/>
|
||||
<xacro:property name="hip_com_z" value="-0.000015"/>
|
||||
<xacro:property name="hip_ixx" value="0.002903894"/>
|
||||
<xacro:property name="hip_ixy" value="-0.000071850"/>
|
||||
<xacro:property name="hip_ixz" value="-0.000001262"/>
|
||||
<xacro:property name="hip_iyy" value="0.004907517"/>
|
||||
<xacro:property name="hip_iyz" value="-0.00000175"/>
|
||||
<xacro:property name="hip_izz" value="0.005586944"/>
|
||||
|
||||
<!-- thigh -->
|
||||
<xacro:property name="thigh_mass" value="0.639"/>
|
||||
<xacro:property name="thigh_com_x" value="-0.005607"/>
|
||||
<xacro:property name="thigh_com_y" value="-0.003877"/>
|
||||
<xacro:property name="thigh_com_z" value="-0.048199"/>
|
||||
<xacro:property name="thigh_ixx" value="0.005666803"/>
|
||||
<xacro:property name="thigh_ixy" value="0.000003597"/>
|
||||
<xacro:property name="thigh_ixz" value="0.000491446"/>
|
||||
<xacro:property name="thigh_iyy" value="0.005847229"/>
|
||||
<xacro:property name="thigh_iyz" value="0.000010086"/>
|
||||
<xacro:property name="thigh_izz" value="0.000369811"/>
|
||||
|
||||
<!-- calf -->
|
||||
<xacro:property name="calf_mass" value="0.207"/>
|
||||
<xacro:property name="calf_com_x" value="0.002781"/>
|
||||
<xacro:property name="calf_com_y" value="0.000063"/>
|
||||
<xacro:property name="calf_com_z" value="-0.142518"/>
|
||||
<xacro:property name="calf_ixx" value="0.006341369"/>
|
||||
<xacro:property name="calf_ixy" value="-0.000000003"/>
|
||||
<xacro:property name="calf_ixz" value="-0.000087951"/>
|
||||
<xacro:property name="calf_iyy" value="0.006355157"/>
|
||||
<xacro:property name="calf_iyz" value="-0.000001336"/>
|
||||
<xacro:property name="calf_izz" value="0.000039188"/>
|
||||
|
||||
<!-- foot -->
|
||||
<xacro:property name="foot_mass" value="0.06"/>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,266 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/aliengo_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of trunk center. -->
|
||||
<gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>10</frequency>
|
||||
<plot>
|
||||
<link>base</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
|
||||
<!-- <gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>100</frequency>
|
||||
<plot>
|
||||
<link>FL_foot</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Green</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
|
||||
<bodyName>trunk</bodyName>
|
||||
<topicName>/apply_force/trunk</topicName>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>trunk_imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>1000.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Foot contacts. -->
|
||||
<gazebo reference="FR_calf">
|
||||
<sensor name="FR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<sensor name="FL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<sensor name="RR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<sensor name="RL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Visualization of Foot contacts. -->
|
||||
<gazebo reference="FR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="base">
|
||||
<material>Gazebo/Green</material>
|
||||
<turnGravityOff>false</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="stick_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/White</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- FL leg -->
|
||||
<gazebo reference="FL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- FR leg -->
|
||||
<gazebo reference="FR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RL leg -->
|
||||
<gazebo reference="RL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RR leg -->
|
||||
<gazebo reference="RR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,176 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae *origin">
|
||||
|
||||
<joint name="${name}_hip_joint" type="revolute">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<xacro:if value="${(mirror_dae == True)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_position_min}" upper="${hip_position_max}"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}" upper="${-hip_position_min}"/>
|
||||
</xacro:if>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_hip">
|
||||
<visual>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 ${hip_offset*mirror} 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||
<mass value="${hip_mass}"/>
|
||||
<inertia
|
||||
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||
izz="${hip_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- <joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint> -->
|
||||
|
||||
<!-- this link is only for collision -->
|
||||
<!-- <link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link> -->
|
||||
|
||||
<joint name="${name}_thigh_joint" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<xacro:if value="${mirror_dae == True}">
|
||||
<mesh filename="package://aliengo_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${mirror_dae == False}">
|
||||
<mesh filename="package://aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||
<mass value="${thigh_mass}"/>
|
||||
<inertia
|
||||
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||
izz="${thigh_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
<child link="${name}_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}" upper="${calf_position_max}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||
<mass value="${calf_mass}"/>
|
||||
<inertia
|
||||
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||
izz="${calf_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||
<parent link="${name}_calf"/>
|
||||
<child link="${name}_foot"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius-0.01}"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${foot_mass}"/>
|
||||
<inertia
|
||||
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:leg_transmission name="${name}"/>
|
||||
</xacro:macro>
|
||||
</robot>
|
|
@ -0,0 +1,40 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="silver">
|
||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="orange">
|
||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="brown">
|
||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,144 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="aliengo_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/leg.xacro"/>
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/gazebo.xacro"/>
|
||||
|
||||
<!-- Rollover Protection mode will add an additional stick on the top, use "true" or "false" to switch it. -->
|
||||
<xacro:property name="rolloverProtection" value="false"/>
|
||||
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<!-- <xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if> -->
|
||||
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- <collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
||||
<mass value="${trunk_mass}"/>
|
||||
<inertia
|
||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||
izz="${trunk_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${(rolloverProtection == 'true')}">
|
||||
<joint name="stick_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="stick_link"/>
|
||||
<origin rpy="0 0 0" xyz="${0.18} 0 ${stick_length/2.0+0.08}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stick_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${stick_mass}"/>
|
||||
<inertia
|
||||
ixx="${stick_mass / 2.0 * (stick_radius*stick_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}" iyz="0.0"
|
||||
izz="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,46 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:property name="stair_length" value="0.640" />
|
||||
<xacro:property name="stair_width" value="0.310" />
|
||||
<xacro:property name="stair_height" value="0.170" />
|
||||
|
||||
<xacro:macro name="stairs" params="stairs xpos ypos zpos">
|
||||
|
||||
<joint name="stair_joint_origin" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="stair_link_${stairs}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stair_link_${stairs}">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
<origin rpy="0 0 0" xyz="${xpos} ${ypos} ${zpos}"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.80"/>
|
||||
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${stairs}">
|
||||
<xacro:stairs stairs="${stairs-1}" xpos="0" ypos="${ypos-stair_width/2}" zpos="${zpos+stair_height}"/>
|
||||
<joint name="stair_joint_${stairs}" type="fixed">
|
||||
<parent link="stair_link_${stairs}"/>
|
||||
<child link="stair_link_${stairs-1}"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,42 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="leg_transmission" params="name">
|
||||
|
||||
<transmission name="${name}_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,19 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(laikago_description)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
genmsg
|
||||
roscpp
|
||||
std_msgs
|
||||
tf
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
)
|
||||
|
||||
include_directories(
|
||||
# include
|
||||
${Boost_INCLUDE_DIR}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
|
@ -0,0 +1,70 @@
|
|||
laikago_gazebo:
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 1000
|
||||
|
||||
# FL Controllers ---------------------------------------
|
||||
FL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# FR Controllers ---------------------------------------
|
||||
FR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RL Controllers ---------------------------------------
|
||||
RL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RR Controllers ---------------------------------------
|
||||
RR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
|
@ -0,0 +1,265 @@
|
|||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /State1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 414
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.588679016
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.0299999993
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
FL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
RL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh_shoulder:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
trunk:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/Axes
|
||||
Enabled: false
|
||||
Length: 1
|
||||
Name: Axes
|
||||
Radius: 0.100000001
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: false
|
||||
- Class: rviz/TF
|
||||
Enabled: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: false
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 238; 238; 238
|
||||
Default Light: true
|
||||
Fixed Frame: base
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Topic: /initialpose
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 1.61842203
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.0599999987
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0.0760490671
|
||||
Y: 0.114219323
|
||||
Z: -0.157691121
|
||||
Focal Shape Fixed Size: false
|
||||
Focal Shape Size: 0.0500000007
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.00999999978
|
||||
Pitch: 0.589797318
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 5.11356974
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 627
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000022dfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000022d000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d00650000000000000006400000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000002e40000022d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1108
|
||||
X: 812
|
||||
Y: 241
|
|
@ -0,0 +1,23 @@
|
|||
<launch>
|
||||
|
||||
<arg name="user_debug" default="false"/>
|
||||
|
||||
<param name="robot_description" command="$(find xacro)/xacro '$(find laikago_description)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug)"/>
|
||||
|
||||
<!-- for higher robot_state_publisher average rate-->
|
||||
<!-- <param name="rate" value="1000"/> -->
|
||||
|
||||
<!-- send fake joint values -->
|
||||
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher">
|
||||
<param name="use_gui" value="TRUE"/>
|
||||
</node>
|
||||
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
|
||||
<param name="publish_frequency" type="double" value="1000.0"/>
|
||||
</node>
|
||||
|
||||
<node pkg="rviz" type="rviz" name="rviz" respawn="false" output="screen"
|
||||
args="-d $(find laikago_description)/launch/check_joint.rviz"/>
|
||||
|
||||
</launch>
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,13 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>laikago_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The laikago_description package</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<depend>roscpp</depend>
|
||||
<depend>std_msgs</depend>
|
||||
</package>
|
|
@ -0,0 +1,541 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="laikago_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.01675"/>
|
||||
<geometry>
|
||||
<box size="0.5616 0.172 0.1875"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.002284 -4.1e-05 0.025165"/>
|
||||
<mass value="13.733"/>
|
||||
<inertia ixx="0.073348887" ixy="0.00030338" ixz="0.001918218" iyy="0.250684593" iyz="-7.5402e-05" izz="0.254469458"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.21935 -0.0875 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-1.0471975512" upper="0.872664625997" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.021 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.001568 0.008134 0.000864"/>
|
||||
<mass value="1.096"/>
|
||||
<inertia ixx="0.000822113" ixy="4.982e-06" ixz="-3.672e-05" iyy="0.000983196" iyz="-2.811e-06" izz="0.000864753"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.059 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.044"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.037 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.034 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.000482 -0.02001 -0.031996"/>
|
||||
<mass value="1.528"/>
|
||||
<inertia ixx="0.00991611" ixy="-1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="8.511e-05" izz="0.00178256"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FR_calf"/>
|
||||
<child link="FR_foot"/>
|
||||
</joint>
|
||||
<link name="FR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.21935 0.0875 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.872664625997" upper="1.0471975512" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.021 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.001568 -0.008134 0.000864"/>
|
||||
<mass value="1.096"/>
|
||||
<inertia ixx="0.000822113" ixy="-4.982e-06" ixz="-3.672e-05" iyy="0.000983196" iyz="2.811e-06" izz="0.000864753"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.059 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.044"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.037 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.034 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.000482 0.02001 -0.031996"/>
|
||||
<mass value="1.528"/>
|
||||
<inertia ixx="0.00991611" ixy="1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="-8.511e-05" izz="0.00178256"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="FL_calf"/>
|
||||
<child link="FL_foot"/>
|
||||
</joint>
|
||||
<link name="FL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.21935 -0.0875 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-1.0471975512" upper="0.872664625997" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.021 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.001568 0.008134 0.000864"/>
|
||||
<mass value="1.096"/>
|
||||
<inertia ixx="0.000822113" ixy="-4.982e-06" ixz="3.672e-05" iyy="0.000983196" iyz="-2.811e-06" izz="0.000864753"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.059 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.044"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.037 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.034 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.000482 -0.02001 -0.031996"/>
|
||||
<mass value="1.528"/>
|
||||
<inertia ixx="0.00991611" ixy="-1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="8.511e-05" izz="0.00178256"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RR_calf"/>
|
||||
<child link="RR_foot"/>
|
||||
</joint>
|
||||
<link name="RR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.21935 0.0875 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.872664625997" upper="1.0471975512" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.021 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.001568 -0.008134 0.000864"/>
|
||||
<mass value="1.096"/>
|
||||
<inertia ixx="0.000822113" ixy="4.982e-06" ixz="3.672e-05" iyy="0.000983196" iyz="2.811e-06" izz="0.000864753"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.059 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.044"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.037 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.034 0.043"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.000482 0.02001 -0.031996"/>
|
||||
<mass value="1.528"/>
|
||||
<inertia ixx="0.00991611" ixy="1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="-8.511e-05" izz="0.00178256"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
<geometry>
|
||||
<box size="0.25 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
|
||||
<parent link="RL_calf"/>
|
||||
<child link="RL_foot"/>
|
||||
</joint>
|
||||
<link name="RL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0265"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</robot>
|
||||
|
|
@ -0,0 +1,104 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="laikago_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- Constants for robot dimensions -->
|
||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||
<xacro:property name="stick_mass" value="0.00001"/>
|
||||
|
||||
<!-- simplified collision value -->
|
||||
<xacro:property name="trunk_width" value="0.172"/>
|
||||
<xacro:property name="trunk_length" value="0.5616"/>
|
||||
<xacro:property name="trunk_height" value="0.1875"/>
|
||||
<xacro:property name="hip_radius" value="0.041"/>
|
||||
<xacro:property name="hip_length" value="0.08"/>
|
||||
<xacro:property name="thigh_shoulder_radius" value="0.044"/>
|
||||
<xacro:property name="thigh_shoulder_length" value="0.08"/>
|
||||
<xacro:property name="thigh_width" value="0.034"/>
|
||||
<xacro:property name="thigh_height" value="0.043"/>
|
||||
<xacro:property name="calf_width" value="0.016"/>
|
||||
<xacro:property name="calf_height" value="0.016"/>
|
||||
<xacro:property name="foot_radius" value="0.0265"/>
|
||||
<xacro:property name="stick_radius" value="0.01"/>
|
||||
<xacro:property name="stick_length" value="0.2"/>
|
||||
|
||||
<!-- kinematic value -->
|
||||
<xacro:property name="thigh_offset" value="0.037"/>
|
||||
<xacro:property name="thigh_length" value="0.25"/>
|
||||
<xacro:property name="calf_length" value="0.25"/>
|
||||
|
||||
<!-- leg offset from trunk center value -->
|
||||
<xacro:property name="leg_offset_x" value="0.21935"/>
|
||||
<xacro:property name="leg_offset_y" value="0.0875"/>
|
||||
<xacro:property name="trunk_offset_z" value="0.01675"/>
|
||||
<xacro:property name="hip_offset" value="0.019"/>
|
||||
|
||||
<!-- joint limits -->
|
||||
<xacro:property name="damping" value="0"/>
|
||||
<xacro:property name="friction" value="0"/>
|
||||
<xacro:property name="hip_max" value="60"/>
|
||||
<xacro:property name="hip_min" value="-50"/>
|
||||
<xacro:property name="hip_velocity_max" value="52.4"/>
|
||||
<xacro:property name="hip_torque_max" value="20"/>
|
||||
<xacro:property name="thigh_max" value="225"/>
|
||||
<xacro:property name="thigh_min" value="-30"/>
|
||||
<xacro:property name="thigh_velocity_max" value="28.6"/>
|
||||
<xacro:property name="thigh_torque_max" value="55"/>
|
||||
<xacro:property name="calf_max" value="-35"/>
|
||||
<xacro:property name="calf_min" value="-159"/>
|
||||
<xacro:property name="calf_velocity_max" value="28.6"/>
|
||||
<xacro:property name="calf_torque_max" value="55"/>
|
||||
|
||||
<!-- dynamics inertial value -->
|
||||
<!-- trunk -->
|
||||
<xacro:property name="trunk_mass" value="13.733"/>
|
||||
<xacro:property name="trunk_com_x" value="0.002284"/>
|
||||
<xacro:property name="trunk_com_y" value="-0.000041"/>
|
||||
<xacro:property name="trunk_com_z" value="0.025165"/>
|
||||
<xacro:property name="trunk_ixx" value="0.073348887"/>
|
||||
<xacro:property name="trunk_ixy" value="0.00030338"/>
|
||||
<xacro:property name="trunk_ixz" value="0.001918218"/>
|
||||
<xacro:property name="trunk_iyy" value="0.250684593"/>
|
||||
<xacro:property name="trunk_iyz" value="-0.000075402"/>
|
||||
<xacro:property name="trunk_izz" value="0.254469458"/>
|
||||
|
||||
<!-- hip (left front) -->
|
||||
<xacro:property name="hip_mass" value="1.096"/>
|
||||
<xacro:property name="hip_com_x" value="-0.001568"/>
|
||||
<xacro:property name="hip_com_y" value="-0.008134"/>
|
||||
<xacro:property name="hip_com_z" value="0.000864"/>
|
||||
<xacro:property name="hip_ixx" value="0.000822113"/>
|
||||
<xacro:property name="hip_ixy" value="-0.000004982"/>
|
||||
<xacro:property name="hip_ixz" value="-0.00003672"/>
|
||||
<xacro:property name="hip_iyy" value="0.000983196"/>
|
||||
<xacro:property name="hip_iyz" value="0.000002811"/>
|
||||
<xacro:property name="hip_izz" value="0.000864753"/>
|
||||
|
||||
<!-- thigh -->
|
||||
<xacro:property name="thigh_mass" value="1.528"/>
|
||||
<xacro:property name="thigh_com_x" value="-0.000482"/>
|
||||
<xacro:property name="thigh_com_y" value="0.02001"/>
|
||||
<xacro:property name="thigh_com_z" value="-0.031996"/>
|
||||
<xacro:property name="thigh_ixx" value="0.00991611"/>
|
||||
<xacro:property name="thigh_ixy" value="0.000010388"/>
|
||||
<xacro:property name="thigh_ixz" value="0.000250428"/>
|
||||
<xacro:property name="thigh_iyy" value="0.009280083"/>
|
||||
<xacro:property name="thigh_iyz" value="-0.00008511"/>
|
||||
<xacro:property name="thigh_izz" value="0.00178256"/>
|
||||
|
||||
<!-- calf -->
|
||||
<xacro:property name="calf_mass" value="0.241"/>
|
||||
<xacro:property name="calf_com_x" value="-0.002196"/>
|
||||
<xacro:property name="calf_com_y" value="-0.000381"/>
|
||||
<xacro:property name="calf_com_z" value="-0.12338"/>
|
||||
<xacro:property name="calf_ixx" value="0.006181961"/>
|
||||
<xacro:property name="calf_ixy" value="0.000000237"/>
|
||||
<xacro:property name="calf_ixz" value="-0.000002985"/>
|
||||
<xacro:property name="calf_iyy" value="0.006196546"/>
|
||||
<xacro:property name="calf_iyz" value="0.000005138"/>
|
||||
<xacro:property name="calf_izz" value="0.000034774"/>
|
||||
|
||||
<!-- foot -->
|
||||
<xacro:property name="foot_mass" value="0.06"/>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,266 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/laikago_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of trunk center. -->
|
||||
<gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>10</frequency>
|
||||
<plot>
|
||||
<link>base</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
|
||||
<!-- <gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>100</frequency>
|
||||
<plot>
|
||||
<link>FL_foot</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Green</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
|
||||
<bodyName>trunk</bodyName>
|
||||
<topicName>/apply_force/trunk</topicName>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>trunk_imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>1000.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Foot contacts. -->
|
||||
<gazebo reference="FR_calf">
|
||||
<sensor name="FR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<sensor name="FL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<sensor name="RR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<sensor name="RL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Visualization of Foot contacts. -->
|
||||
<gazebo reference="FR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="base">
|
||||
<material>Gazebo/Green</material>
|
||||
<turnGravityOff>false</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="stick_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/White</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- FL leg -->
|
||||
<gazebo reference="FL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- FR leg -->
|
||||
<gazebo reference="FR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RL leg -->
|
||||
<gazebo reference="RL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RR leg -->
|
||||
<gazebo reference="RR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,176 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find laikago_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae *origin">
|
||||
|
||||
<joint name="${name}_hip_joint" type="revolute">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<xacro:if value="${(mirror_dae == True)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_min*PI/180.0}" upper="${hip_max*PI/180.0}"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_max*PI/180.0}" upper="${-hip_min*PI/180.0}"/>
|
||||
</xacro:if>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_hip">
|
||||
<visual>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<geometry>
|
||||
<mesh filename="package://laikago_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 ${-(hip_length/2.0-hip_offset)*mirror} 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||
<mass value="${hip_mass}"/>
|
||||
<inertia
|
||||
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||
izz="${hip_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint>
|
||||
|
||||
<!-- this link is only for collision -->
|
||||
<link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_min*PI/180.0}" upper="${thigh_max*PI/180.0}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<xacro:if value="${mirror_dae == True}">
|
||||
<mesh filename="package://laikago_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${mirror_dae == False}">
|
||||
<mesh filename="package://laikago_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||
<mass value="${thigh_mass}"/>
|
||||
<inertia
|
||||
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||
izz="${thigh_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
<child link="${name}_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_min*PI/180.0}" upper="${calf_max*PI/180.0}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://laikago_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||
<mass value="${calf_mass}"/>
|
||||
<inertia
|
||||
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||
izz="${calf_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||
<parent link="${name}_calf"/>
|
||||
<child link="${name}_foot"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius-0.01}"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${foot_mass}"/>
|
||||
<inertia
|
||||
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:leg_transmission name="${name}"/>
|
||||
</xacro:macro>
|
||||
</robot>
|
|
@ -0,0 +1,40 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="silver">
|
||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="orange">
|
||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="brown">
|
||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,135 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="laikago_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find laikago_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find laikago_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find laikago_description)/xacro/leg.xacro"/>
|
||||
<xacro:include filename="$(find laikago_description)/xacro/gazebo.xacro"/>
|
||||
|
||||
<!-- Rollover Protection mode will add an additional stick on the top, use "true" or "false" to switch it. -->
|
||||
<xacro:property name="rolloverProtection" value="false"/>
|
||||
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://laikago_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 ${trunk_offset_z}"/>
|
||||
<geometry>
|
||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
||||
<mass value="${trunk_mass}"/>
|
||||
<inertia
|
||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||
izz="${trunk_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${(rolloverProtection == 'true')}">
|
||||
<joint name="stick_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="stick_link"/>
|
||||
<origin rpy="0 0 0" xyz="${0.18} 0 ${stick_length/2.0+0.08}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stick_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${stick_mass}"/>
|
||||
<inertia
|
||||
ixx="${stick_mass / 2.0 * (stick_radius*stick_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}" iyz="0.0"
|
||||
izz="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae="False" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,42 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="leg_transmission" params="name">
|
||||
|
||||
<transmission name="${name}_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,57 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_controller)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
controller_manager
|
||||
genmsg
|
||||
joint_state_controller
|
||||
robot_state_publisher
|
||||
roscpp
|
||||
gazebo_ros
|
||||
std_msgs
|
||||
tf
|
||||
geometry_msgs
|
||||
unitree_legged_msgs
|
||||
)
|
||||
|
||||
find_package(gazebo REQUIRED)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
unitree_legged_msgs
|
||||
)
|
||||
|
||||
include_directories(
|
||||
include
|
||||
${Boost_INCLUDE_DIR}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${GAZEBO_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
link_directories(${GAZEBO_LIBRARY_DIRS})
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
|
||||
|
||||
# Declare a C++ library
|
||||
add_library(${PROJECT_NAME}
|
||||
src/body.cpp
|
||||
)
|
||||
|
||||
add_dependencies(${PROJECT_NAME} unitree_legged_msgs_gencpp)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
${catkin_LIBRARIES} ${EXTRA_LIBS}
|
||||
)
|
||||
|
||||
# add_library(unitreeFootContactPlugin SHARED plugin/foot_contact_plugin.cc)
|
||||
# target_link_libraries(unitreeFootContactPlugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})
|
||||
|
||||
# add_library(unitreeDrawForcePlugin SHARED plugin/draw_force_plugin.cc)
|
||||
# target_link_libraries(unitreeDrawForcePlugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})
|
||||
|
||||
add_executable(unitree_external_force src/external_force.cpp)
|
||||
target_link_libraries(unitree_external_force ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(unitree_servo src/servo.cpp)
|
||||
target_link_libraries(unitree_servo ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
|
||||
|
|
@ -0,0 +1,29 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#ifndef __BODY_H__
|
||||
#define __BODY_H__
|
||||
|
||||
#include "ros/ros.h"
|
||||
#include "unitree_legged_msgs/LowCmd.h"
|
||||
#include "unitree_legged_msgs/LowState.h"
|
||||
#include "unitree_legged_msgs/HighState.h"
|
||||
#define PosStopF (2.146E+9f)
|
||||
#define VelStopF (16000.f)
|
||||
|
||||
namespace unitree_model {
|
||||
|
||||
extern ros::Publisher servo_pub[12];
|
||||
extern ros::Publisher highState_pub;
|
||||
extern unitree_legged_msgs::LowCmd lowCmd;
|
||||
extern unitree_legged_msgs::LowState lowState;
|
||||
|
||||
void stand();
|
||||
void motion_init();
|
||||
void sendServoCmd();
|
||||
void moveAllPosition(double* jointPositions, double duration);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,7 @@
|
|||
<launch>
|
||||
<arg name="rname" default="laikago"/>
|
||||
<param name="robot_name" value="$(arg rname)"/>
|
||||
|
||||
<!-- <node pkg="unitree_controller" type="unitree_servo" name="unitree_servo" respawn="true"/> -->
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,34 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_controller</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The unitree_controller package.</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<buildtool_depend>genmsg</buildtool_depend>
|
||||
<build_depend>controller_manager</build_depend>
|
||||
<build_depend>joint_state_controller</build_depend>
|
||||
<build_depend>robot_state_publisher</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_export_depend>controller_manager</build_export_depend>
|
||||
<build_export_depend>joint_state_controller</build_export_depend>
|
||||
<build_export_depend>robot_state_publisher</build_export_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<exec_depend>controller_manager</exec_depend>
|
||||
<exec_depend>joint_state_controller</exec_depend>
|
||||
<exec_depend>robot_state_publisher</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<depend>unitree_legged_msgs</depend>
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
<!-- <gazebo_ros plugin_path="${prefix}/lib" gazebo_media_path="${prefix}"/> -->
|
||||
</export>
|
||||
</package>
|
|
@ -0,0 +1,77 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include "body.h"
|
||||
|
||||
namespace unitree_model {
|
||||
|
||||
ros::Publisher servo_pub[12];
|
||||
unitree_legged_msgs::LowCmd lowCmd;
|
||||
unitree_legged_msgs::LowState lowState;
|
||||
|
||||
// These parameters are only for reference.
|
||||
// Actual patameters need to be debugged if you want to run on real robot.
|
||||
void paramInit()
|
||||
{
|
||||
for(int i=0; i<4; i++){
|
||||
lowCmd.motorCmd[i*3+0].mode = 0x0A;
|
||||
lowCmd.motorCmd[i*3+0].Kp = 70;
|
||||
lowCmd.motorCmd[i*3+0].dq = 0;
|
||||
lowCmd.motorCmd[i*3+0].Kd = 3;
|
||||
lowCmd.motorCmd[i*3+0].tau = 0;
|
||||
lowCmd.motorCmd[i*3+1].mode = 0x0A;
|
||||
lowCmd.motorCmd[i*3+1].Kp = 180;
|
||||
lowCmd.motorCmd[i*3+1].dq = 0;
|
||||
lowCmd.motorCmd[i*3+1].Kd = 8;
|
||||
lowCmd.motorCmd[i*3+1].tau = 0;
|
||||
lowCmd.motorCmd[i*3+2].mode = 0x0A;
|
||||
lowCmd.motorCmd[i*3+2].Kp = 300;
|
||||
lowCmd.motorCmd[i*3+2].dq = 0;
|
||||
lowCmd.motorCmd[i*3+2].Kd = 15;
|
||||
lowCmd.motorCmd[i*3+2].tau = 0;
|
||||
}
|
||||
for(int i=0; i<12; i++){
|
||||
lowCmd.motorCmd[i].q = lowState.motorState[i].q;
|
||||
}
|
||||
}
|
||||
|
||||
void stand()
|
||||
{
|
||||
double pos[12] = {0.0, 0.67, -1.3, -0.0, 0.67, -1.3,
|
||||
0.0, 0.67, -1.3, -0.0, 0.67, -1.3};
|
||||
moveAllPosition(pos, 2*1000);
|
||||
}
|
||||
|
||||
void motion_init()
|
||||
{
|
||||
paramInit();
|
||||
stand();
|
||||
}
|
||||
|
||||
void sendServoCmd()
|
||||
{
|
||||
for(int m=0; m<12; m++){
|
||||
servo_pub[m].publish(lowCmd.motorCmd[m]);
|
||||
}
|
||||
ros::spinOnce();
|
||||
usleep(1000);
|
||||
}
|
||||
|
||||
void moveAllPosition(double* targetPos, double duration)
|
||||
{
|
||||
double pos[12] ,lastPos[12], percent;
|
||||
for(int j=0; j<12; j++) lastPos[j] = lowState.motorState[j].q;
|
||||
for(int i=1; i<=duration; i++){
|
||||
if(!ros::ok()) break;
|
||||
percent = (double)i/duration;
|
||||
for(int j=0; j<12; j++){
|
||||
lowCmd.motorCmd[j].q = lastPos[j]*(1-percent) + targetPos[j]*percent;
|
||||
}
|
||||
sendServoCmd();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
|
@ -0,0 +1,166 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <geometry_msgs/Wrench.h>
|
||||
#include <signal.h>
|
||||
#include <termios.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#define KEYCODE_UP 0x41
|
||||
#define KEYCODE_DOWN 0x42
|
||||
#define KEYCODE_LEFT 0x44
|
||||
#define KEYCODE_RIGHT 0x43
|
||||
#define KEYCODE_SPACE 0x20
|
||||
|
||||
int mode = 1; // pulsed mode or continuous mode
|
||||
|
||||
class teleForceCmd
|
||||
{
|
||||
public:
|
||||
teleForceCmd();
|
||||
void keyLoop();
|
||||
void pubForce(double x, double y, double z);
|
||||
private:
|
||||
double Fx, Fy, Fz;
|
||||
ros::NodeHandle n;
|
||||
ros::Publisher force_pub;
|
||||
geometry_msgs::Wrench Force;
|
||||
};
|
||||
|
||||
teleForceCmd::teleForceCmd()
|
||||
{
|
||||
Fx = 0;
|
||||
Fy = 0;
|
||||
Fz = 0;
|
||||
force_pub = n.advertise<geometry_msgs::Wrench>("/apply_force/trunk", 20);
|
||||
sleep(1);
|
||||
pubForce(Fx, Fy, Fz);
|
||||
}
|
||||
|
||||
int kfd = 0;
|
||||
struct termios cooked, raw;
|
||||
|
||||
void quit(int sig)
|
||||
{
|
||||
tcsetattr(kfd, TCSANOW, &cooked);
|
||||
ros::shutdown();
|
||||
exit(0);
|
||||
}
|
||||
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
ros::init(argc, argv, "external_force");
|
||||
teleForceCmd remote;
|
||||
signal(SIGINT,quit);
|
||||
remote.keyLoop();
|
||||
return(0);
|
||||
}
|
||||
|
||||
void teleForceCmd::pubForce(double x, double y, double z)
|
||||
{
|
||||
Force.force.x = Fx;
|
||||
Force.force.y = Fy;
|
||||
Force.force.z = Fz;
|
||||
force_pub.publish(Force);
|
||||
ros::spinOnce();
|
||||
}
|
||||
|
||||
void teleForceCmd::keyLoop()
|
||||
{
|
||||
char c;
|
||||
bool dirty=false;
|
||||
// get the console in raw mode
|
||||
tcgetattr(kfd, &cooked);
|
||||
memcpy(&raw, &cooked, sizeof(struct termios));
|
||||
raw.c_lflag &=~ (ICANON | ECHO);
|
||||
// Setting a new line, then end of file
|
||||
raw.c_cc[VEOL] = 1;
|
||||
raw.c_cc[VEOF] = 2;
|
||||
tcsetattr(kfd, TCSANOW, &raw);
|
||||
puts("Reading from keyboard");
|
||||
puts("---------------------------");
|
||||
puts("Use 'Space' to change mode, default is Pulsed mode:");
|
||||
puts("Use 'Up/Down/Left/Right' to change direction");
|
||||
for(;;){
|
||||
// get the next event from the keyboard
|
||||
if(read(kfd, &c, 1) < 0){
|
||||
perror("read():");
|
||||
exit(-1);
|
||||
}
|
||||
ROS_DEBUG("value: 0x%02X\n", c);
|
||||
switch(c){
|
||||
case KEYCODE_UP:
|
||||
if(mode > 0) {
|
||||
Fx = 60;
|
||||
} else {
|
||||
Fx += 16;
|
||||
if(Fx > 220) Fx = 220;
|
||||
if(Fx < -220) Fx = -220;
|
||||
}
|
||||
ROS_INFO("Fx:%3d Fy:%3d Fz:%3d", (int)Fx, (int)Fy, (int)Fz);
|
||||
dirty = true;
|
||||
break;
|
||||
case KEYCODE_DOWN:
|
||||
if(mode > 0) {
|
||||
Fx = -60;
|
||||
} else {
|
||||
Fx -= 16;
|
||||
if(Fx > 220) Fx = 220;
|
||||
if(Fx < -220) Fx = -220;
|
||||
}
|
||||
ROS_INFO("Fx:%3d Fy:%3d Fz:%3d", (int)Fx, (int)Fy, (int)Fz);
|
||||
dirty = true;
|
||||
break;
|
||||
case KEYCODE_LEFT:
|
||||
if(mode > 0) {
|
||||
Fy = 30;
|
||||
} else {
|
||||
Fy += 8;
|
||||
if(Fy > 220) Fy = 220;
|
||||
if(Fy < -220) Fy = -220;
|
||||
}
|
||||
ROS_INFO("Fx:%3d Fy:%3d Fz:%3d", (int)Fx, (int)Fy, (int)Fz);
|
||||
dirty = true;
|
||||
break;
|
||||
case KEYCODE_RIGHT:
|
||||
if(mode > 0) {
|
||||
Fy = -30;
|
||||
} else {
|
||||
Fy -= 8;
|
||||
if(Fy > 220) Fy = 220;
|
||||
if(Fy < -220) Fy = -220;
|
||||
}
|
||||
ROS_INFO("Fx:%3d Fy:%3d Fz:%3d", (int)Fx, (int)Fy, (int)Fz);
|
||||
dirty = true;
|
||||
break;
|
||||
case KEYCODE_SPACE:
|
||||
mode = mode*(-1);
|
||||
if(mode > 0){
|
||||
ROS_INFO("Change to Pulsed mode.");
|
||||
} else {
|
||||
ROS_INFO("Change to Continuous mode.");
|
||||
}
|
||||
Fx = 0;
|
||||
Fy = 0;
|
||||
Fz = 0;
|
||||
ROS_INFO("Fx:%3d Fy:%3d Fz:%3d", (int)Fx, (int)Fy, (int)Fz);
|
||||
dirty = true;
|
||||
break;
|
||||
}
|
||||
if(dirty == true){
|
||||
pubForce(Fx, Fy, Fz);
|
||||
if(mode > 0){
|
||||
usleep(100000); // 100 ms
|
||||
Fx = 0;
|
||||
Fy = 0;
|
||||
Fz = 0;
|
||||
pubForce(Fx, Fy, Fz);
|
||||
}
|
||||
dirty=false;
|
||||
}
|
||||
}
|
||||
return;
|
||||
}
|
|
@ -0,0 +1,238 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include "ros/ros.h"
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include "unitree_legged_msgs/LowCmd.h"
|
||||
#include "unitree_legged_msgs/LowState.h"
|
||||
#include "unitree_legged_msgs/MotorCmd.h"
|
||||
#include "unitree_legged_msgs/MotorState.h"
|
||||
#include <geometry_msgs/WrenchStamped.h>
|
||||
#include <sensor_msgs/Imu.h>
|
||||
#include <std_msgs/Bool.h>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include <math.h>
|
||||
#include <nav_msgs/Odometry.h>
|
||||
#include "body.h"
|
||||
|
||||
using namespace std;
|
||||
using namespace unitree_model;
|
||||
|
||||
bool start_up = true;
|
||||
|
||||
class multiThread
|
||||
{
|
||||
public:
|
||||
multiThread(string rname){
|
||||
robot_name = rname;
|
||||
imu_sub = nm.subscribe("/trunk_imu", 1, &multiThread::imuCallback, this);
|
||||
footForce_sub[0] = nm.subscribe("/visual/FR_foot_contact/the_force", 1, &multiThread::FRfootCallback, this);
|
||||
footForce_sub[1] = nm.subscribe("/visual/FL_foot_contact/the_force", 1, &multiThread::FLfootCallback, this);
|
||||
footForce_sub[2] = nm.subscribe("/visual/RR_foot_contact/the_force", 1, &multiThread::RRfootCallback, this);
|
||||
footForce_sub[3] = nm.subscribe("/visual/RL_foot_contact/the_force", 1, &multiThread::RLfootCallback, this);
|
||||
servo_sub[0] = nm.subscribe("/" + robot_name + "_gazebo/FR_hip_controller/state", 1, &multiThread::FRhipCallback, this);
|
||||
servo_sub[1] = nm.subscribe("/" + robot_name + "_gazebo/FR_thigh_controller/state", 1, &multiThread::FRthighCallback, this);
|
||||
servo_sub[2] = nm.subscribe("/" + robot_name + "_gazebo/FR_calf_controller/state", 1, &multiThread::FRcalfCallback, this);
|
||||
servo_sub[3] = nm.subscribe("/" + robot_name + "_gazebo/FL_hip_controller/state", 1, &multiThread::FLhipCallback, this);
|
||||
servo_sub[4] = nm.subscribe("/" + robot_name + "_gazebo/FL_thigh_controller/state", 1, &multiThread::FLthighCallback, this);
|
||||
servo_sub[5] = nm.subscribe("/" + robot_name + "_gazebo/FL_calf_controller/state", 1, &multiThread::FLcalfCallback, this);
|
||||
servo_sub[6] = nm.subscribe("/" + robot_name + "_gazebo/RR_hip_controller/state", 1, &multiThread::RRhipCallback, this);
|
||||
servo_sub[7] = nm.subscribe("/" + robot_name + "_gazebo/RR_thigh_controller/state", 1, &multiThread::RRthighCallback, this);
|
||||
servo_sub[8] = nm.subscribe("/" + robot_name + "_gazebo/RR_calf_controller/state", 1, &multiThread::RRcalfCallback, this);
|
||||
servo_sub[9] = nm.subscribe("/" + robot_name + "_gazebo/RL_hip_controller/state", 1, &multiThread::RLhipCallback, this);
|
||||
servo_sub[10] = nm.subscribe("/" + robot_name + "_gazebo/RL_thigh_controller/state", 1, &multiThread::RLthighCallback, this);
|
||||
servo_sub[11] = nm.subscribe("/" + robot_name + "_gazebo/RL_calf_controller/state", 1, &multiThread::RLcalfCallback, this);
|
||||
}
|
||||
|
||||
void imuCallback(const sensor_msgs::Imu & msg)
|
||||
{
|
||||
lowState.imu.quaternion[0] = msg.orientation.w;
|
||||
lowState.imu.quaternion[1] = msg.orientation.x;
|
||||
lowState.imu.quaternion[2] = msg.orientation.y;
|
||||
lowState.imu.quaternion[3] = msg.orientation.z;
|
||||
}
|
||||
|
||||
void FRhipCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
start_up = false;
|
||||
lowState.motorState[0].mode = msg.mode;
|
||||
lowState.motorState[0].q = msg.q;
|
||||
lowState.motorState[0].dq = msg.dq;
|
||||
lowState.motorState[0].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void FRthighCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[1].mode = msg.mode;
|
||||
lowState.motorState[1].q = msg.q;
|
||||
lowState.motorState[1].dq = msg.dq;
|
||||
lowState.motorState[1].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void FRcalfCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[2].mode = msg.mode;
|
||||
lowState.motorState[2].q = msg.q;
|
||||
lowState.motorState[2].dq = msg.dq;
|
||||
lowState.motorState[2].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void FLhipCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
start_up = false;
|
||||
lowState.motorState[3].mode = msg.mode;
|
||||
lowState.motorState[3].q = msg.q;
|
||||
lowState.motorState[3].dq = msg.dq;
|
||||
lowState.motorState[3].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void FLthighCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[4].mode = msg.mode;
|
||||
lowState.motorState[4].q = msg.q;
|
||||
lowState.motorState[4].dq = msg.dq;
|
||||
lowState.motorState[4].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void FLcalfCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[5].mode = msg.mode;
|
||||
lowState.motorState[5].q = msg.q;
|
||||
lowState.motorState[5].dq = msg.dq;
|
||||
lowState.motorState[5].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void RRhipCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
start_up = false;
|
||||
lowState.motorState[6].mode = msg.mode;
|
||||
lowState.motorState[6].q = msg.q;
|
||||
lowState.motorState[6].dq = msg.dq;
|
||||
lowState.motorState[6].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void RRthighCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[7].mode = msg.mode;
|
||||
lowState.motorState[7].q = msg.q;
|
||||
lowState.motorState[7].dq = msg.dq;
|
||||
lowState.motorState[7].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void RRcalfCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[8].mode = msg.mode;
|
||||
lowState.motorState[8].q = msg.q;
|
||||
lowState.motorState[8].dq = msg.dq;
|
||||
lowState.motorState[8].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void RLhipCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
start_up = false;
|
||||
lowState.motorState[9].mode = msg.mode;
|
||||
lowState.motorState[9].q = msg.q;
|
||||
lowState.motorState[9].dq = msg.dq;
|
||||
lowState.motorState[9].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void RLthighCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[10].mode = msg.mode;
|
||||
lowState.motorState[10].q = msg.q;
|
||||
lowState.motorState[10].dq = msg.dq;
|
||||
lowState.motorState[10].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void RLcalfCallback(const unitree_legged_msgs::MotorState& msg)
|
||||
{
|
||||
lowState.motorState[11].mode = msg.mode;
|
||||
lowState.motorState[11].q = msg.q;
|
||||
lowState.motorState[11].dq = msg.dq;
|
||||
lowState.motorState[11].tauEst = msg.tauEst;
|
||||
}
|
||||
|
||||
void FRfootCallback(const geometry_msgs::WrenchStamped& msg)
|
||||
{
|
||||
lowState.eeForce[0].x = msg.wrench.force.x;
|
||||
lowState.eeForce[0].y = msg.wrench.force.y;
|
||||
lowState.eeForce[0].z = msg.wrench.force.z;
|
||||
lowState.footForce[0] = msg.wrench.force.z;
|
||||
}
|
||||
|
||||
void FLfootCallback(const geometry_msgs::WrenchStamped& msg)
|
||||
{
|
||||
lowState.eeForce[1].x = msg.wrench.force.x;
|
||||
lowState.eeForce[1].y = msg.wrench.force.y;
|
||||
lowState.eeForce[1].z = msg.wrench.force.z;
|
||||
lowState.footForce[1] = msg.wrench.force.z;
|
||||
}
|
||||
|
||||
void RRfootCallback(const geometry_msgs::WrenchStamped& msg)
|
||||
{
|
||||
lowState.eeForce[2].x = msg.wrench.force.x;
|
||||
lowState.eeForce[2].y = msg.wrench.force.y;
|
||||
lowState.eeForce[2].z = msg.wrench.force.z;
|
||||
lowState.footForce[2] = msg.wrench.force.z;
|
||||
}
|
||||
|
||||
void RLfootCallback(const geometry_msgs::WrenchStamped& msg)
|
||||
{
|
||||
lowState.eeForce[3].x = msg.wrench.force.x;
|
||||
lowState.eeForce[3].y = msg.wrench.force.y;
|
||||
lowState.eeForce[3].z = msg.wrench.force.z;
|
||||
lowState.footForce[3] = msg.wrench.force.z;
|
||||
}
|
||||
|
||||
private:
|
||||
ros::NodeHandle nm;
|
||||
ros::Subscriber servo_sub[12], footForce_sub[4], imu_sub;
|
||||
string robot_name;
|
||||
};
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "unitree_gazebo_servo");
|
||||
|
||||
string robot_name;
|
||||
ros::param::get("/robot_name", robot_name);
|
||||
cout << "robot_name: " << robot_name << endl;
|
||||
|
||||
multiThread listen_publish_obj(robot_name);
|
||||
ros::AsyncSpinner spinner(1); // one threads
|
||||
spinner.start();
|
||||
usleep(300000); // must wait 300ms, to get first state
|
||||
|
||||
ros::NodeHandle n;
|
||||
ros::Publisher lowState_pub; //for rviz visualization
|
||||
// ros::Rate loop_rate(1000);
|
||||
// the following nodes have been initialized by "gazebo.launch"
|
||||
lowState_pub = n.advertise<unitree_legged_msgs::LowState>("/" + robot_name + "_gazebo/lowState/state", 1);
|
||||
servo_pub[0] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/FR_hip_controller/command", 1);
|
||||
servo_pub[1] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/FR_thigh_controller/command", 1);
|
||||
servo_pub[2] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/FR_calf_controller/command", 1);
|
||||
servo_pub[3] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/FL_hip_controller/command", 1);
|
||||
servo_pub[4] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/FL_thigh_controller/command", 1);
|
||||
servo_pub[5] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/FL_calf_controller/command", 1);
|
||||
servo_pub[6] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/RR_hip_controller/command", 1);
|
||||
servo_pub[7] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/RR_thigh_controller/command", 1);
|
||||
servo_pub[8] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/RR_calf_controller/command", 1);
|
||||
servo_pub[9] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/RL_hip_controller/command", 1);
|
||||
servo_pub[10] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/RL_thigh_controller/command", 1);
|
||||
servo_pub[11] = n.advertise<unitree_legged_msgs::MotorCmd>("/" + robot_name + "_gazebo/RL_calf_controller/command", 1);
|
||||
|
||||
motion_init();
|
||||
|
||||
while (ros::ok()){
|
||||
/*
|
||||
control logic
|
||||
*/
|
||||
lowState_pub.publish(lowState);
|
||||
sendServoCmd();
|
||||
}
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,57 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_gazebo)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
controller_manager
|
||||
genmsg
|
||||
joint_state_controller
|
||||
robot_state_publisher
|
||||
roscpp
|
||||
gazebo_ros
|
||||
std_msgs
|
||||
tf
|
||||
geometry_msgs
|
||||
unitree_legged_msgs
|
||||
)
|
||||
|
||||
find_package(gazebo REQUIRED)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
unitree_legged_msgs
|
||||
)
|
||||
|
||||
include_directories(
|
||||
# include
|
||||
${Boost_INCLUDE_DIR}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${GAZEBO_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
link_directories(${GAZEBO_LIBRARY_DIRS})
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
|
||||
|
||||
# # Declare a C++ library
|
||||
# add_library(${PROJECT_NAME}
|
||||
# src/body.cpp
|
||||
# )
|
||||
|
||||
# add_dependencies(${PROJECT_NAME} unitree_legged_msgs_gencpp)
|
||||
|
||||
# target_link_libraries(${PROJECT_NAME}
|
||||
# ${catkin_LIBRARIES} ${EXTRA_LIBS}
|
||||
# )
|
||||
|
||||
add_library(unitreeFootContactPlugin SHARED plugin/foot_contact_plugin.cc)
|
||||
target_link_libraries(unitreeFootContactPlugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})
|
||||
|
||||
add_library(unitreeDrawForcePlugin SHARED plugin/draw_force_plugin.cc)
|
||||
target_link_libraries(unitreeDrawForcePlugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})
|
||||
|
||||
# add_executable(unitree_external_force src/exe/external_force.cpp)
|
||||
# target_link_libraries(unitree_external_force ${catkin_LIBRARIES})
|
||||
|
||||
# add_executable(unitree_servo src/exe/servo.cpp)
|
||||
# target_link_libraries(unitree_servo ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
<launch>
|
||||
<arg name="wname" default="earth"/>
|
||||
<arg name="rname" default="laikago"/>
|
||||
<arg name="robot_path" value="(find $(arg rname)_description)"/>
|
||||
<arg name="dollar" value="$"/>
|
||||
|
||||
<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)/$(arg wname).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 '$(arg dollar)$(arg robot_path)/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 $(arg rname)_gazebo -param robot_description -unpause"/>
|
||||
|
||||
<!-- Load joint controller configurations from YAML file to parameter server -->
|
||||
<rosparam file="$(arg dollar)$(arg robot_path)/config/robot_control.yaml" command="load"/>
|
||||
|
||||
<!-- load the controllers -->
|
||||
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
|
||||
output="screen" ns="/$(arg rname)_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 "/>
|
||||
|
||||
<!-- convert joint states to TF transforms for rviz, etc -->
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
|
||||
respawn="false" output="screen">
|
||||
<remap from="/joint_states" to="/$(arg rname)_gazebo/joint_states"/>
|
||||
</node>
|
||||
|
||||
<!-- <node pkg="unitree_gazebo" type="servo" name="servo" required="true" output="screen"/> -->
|
||||
|
||||
<!-- load the parameter unitree_controller -->
|
||||
<include file="$(find unitree_controller)/launch/set_ctrl.launch">
|
||||
<arg name="rname" value="$(arg rname)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,34 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_gazebo</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The unitree_gazebo package. It can start a gazebo simulation</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<buildtool_depend>genmsg</buildtool_depend>
|
||||
<build_depend>controller_manager</build_depend>
|
||||
<build_depend>joint_state_controller</build_depend>
|
||||
<build_depend>robot_state_publisher</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_export_depend>controller_manager</build_export_depend>
|
||||
<build_export_depend>joint_state_controller</build_export_depend>
|
||||
<build_export_depend>robot_state_publisher</build_export_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<exec_depend>controller_manager</exec_depend>
|
||||
<exec_depend>joint_state_controller</exec_depend>
|
||||
<exec_depend>robot_state_publisher</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<depend>unitree_legged_msgs</depend>
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
<gazebo_ros plugin_path="${prefix}/lib" gazebo_media_path="${prefix}"/>
|
||||
</export>
|
||||
</package>
|
|
@ -0,0 +1,85 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <ignition/math/Color.hh>
|
||||
#include <gazebo/common/Events.hh>
|
||||
#include <gazebo/msgs/msgs.hh>
|
||||
#include <gazebo/transport/Node.hh>
|
||||
#include <gazebo/common/Plugin.hh>
|
||||
#include <ros/ros.h>
|
||||
#include "gazebo/rendering/DynamicLines.hh"
|
||||
#include "gazebo/rendering/RenderTypes.hh"
|
||||
#include "gazebo/rendering/Visual.hh"
|
||||
#include "gazebo/rendering/Scene.hh"
|
||||
#include <ros/ros.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <geometry_msgs/WrenchStamped.h>
|
||||
|
||||
namespace gazebo
|
||||
{
|
||||
class UnitreeDrawForcePlugin : public VisualPlugin
|
||||
{
|
||||
public:
|
||||
UnitreeDrawForcePlugin():line(NULL){}
|
||||
~UnitreeDrawForcePlugin(){
|
||||
this->visual->DeleteDynamicLine(this->line);
|
||||
}
|
||||
|
||||
void Load(rendering::VisualPtr _parent, sdf::ElementPtr _sdf )
|
||||
{
|
||||
this->visual = _parent;
|
||||
this->visual_namespace = "visual/";
|
||||
if (!_sdf->HasElement("topicName")){
|
||||
ROS_INFO("Force draw plugin missing <topicName>, defaults to /default_force_draw");
|
||||
this->topic_name = "/default_force_draw";
|
||||
} else{
|
||||
this->topic_name = _sdf->Get<std::string>("topicName");
|
||||
}
|
||||
if (!ros::isInitialized()){
|
||||
int argc = 0;
|
||||
char** argv = NULL;
|
||||
ros::init(argc,argv,"gazebo_visual",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
|
||||
}
|
||||
|
||||
this->line = this->visual->CreateDynamicLine(rendering::RENDERING_LINE_STRIP);
|
||||
this->line->AddPoint(ignition::math::Vector3d(0, 0, 0), common::Color(0, 1, 0, 1.0));
|
||||
this->line->AddPoint(ignition::math::Vector3d(1, 1, 1), common::Color(0, 1, 0, 1.0));
|
||||
this->line->setMaterial("Gazebo/Purple");
|
||||
this->line->setVisibilityFlags(GZ_VISIBILITY_GUI);
|
||||
this->visual->SetVisible(true);
|
||||
|
||||
this->rosnode = new ros::NodeHandle(this->visual_namespace);
|
||||
this->force_sub = this->rosnode->subscribe(this->topic_name+"/"+"the_force", 30, &UnitreeDrawForcePlugin::GetForceCallback, this);
|
||||
this->update_connection = event::Events::ConnectPreRender(boost::bind(&UnitreeDrawForcePlugin::OnUpdate, this));
|
||||
ROS_INFO("Load %s Draw Force plugin.", this->topic_name.c_str());
|
||||
}
|
||||
|
||||
void OnUpdate()
|
||||
{
|
||||
this->line->SetPoint(1, ignition::math::Vector3d(Fx, Fy, Fz));
|
||||
}
|
||||
|
||||
void GetForceCallback(const geometry_msgs::WrenchStamped & msg)
|
||||
{
|
||||
Fx = msg.wrench.force.x/20.0;
|
||||
Fy = msg.wrench.force.y/20.0;
|
||||
Fz = msg.wrench.force.z/20.0;
|
||||
// Fx = msg.wrench.force.x;
|
||||
// Fy = msg.wrench.force.y;
|
||||
// Fz = msg.wrench.force.z;
|
||||
}
|
||||
|
||||
private:
|
||||
ros::NodeHandle* rosnode;
|
||||
std::string topic_name;
|
||||
rendering::VisualPtr visual;
|
||||
rendering::DynamicLines *line;
|
||||
std::string visual_namespace;
|
||||
ros::Subscriber force_sub;
|
||||
double Fx=0, Fy=0, Fz=0;
|
||||
event::ConnectionPtr update_connection;
|
||||
};
|
||||
GZ_REGISTER_VISUAL_PLUGIN(UnitreeDrawForcePlugin)
|
||||
}
|
|
@ -0,0 +1,93 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <string>
|
||||
#include <gazebo/common/Events.hh>
|
||||
#include <ros/ros.h>
|
||||
#include <ros/advertise_options.h>
|
||||
#include <gazebo/gazebo.hh>
|
||||
#include <gazebo/sensors/sensors.hh>
|
||||
#include <geometry_msgs/WrenchStamped.h>
|
||||
|
||||
namespace gazebo
|
||||
{
|
||||
class UnitreeFootContactPlugin : public SensorPlugin
|
||||
{
|
||||
public:
|
||||
UnitreeFootContactPlugin() : SensorPlugin(){}
|
||||
~UnitreeFootContactPlugin(){}
|
||||
|
||||
void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
|
||||
{
|
||||
this->parentSensor = std::dynamic_pointer_cast<sensors::ContactSensor>(_sensor); // Make sure the parent sensor is valid.
|
||||
if (!this->parentSensor){
|
||||
gzerr << "UnitreeFootContactPlugin requires a ContactSensor.\n";
|
||||
return;
|
||||
}
|
||||
this->contact_namespace = "contact/";
|
||||
this->rosnode = new ros::NodeHandle(this->contact_namespace);
|
||||
// add "visual" is for the same name of draw node
|
||||
this->force_pub = this->rosnode->advertise<geometry_msgs::WrenchStamped>("/visual/"+_sensor->Name()+"/the_force", 100);
|
||||
// Connect to the sensor update event.
|
||||
this->update_connection = this->parentSensor->ConnectUpdated(std::bind(&UnitreeFootContactPlugin::OnUpdate, this));
|
||||
this->parentSensor->SetActive(true); // Make sure the parent sensor is active.
|
||||
count = 0;
|
||||
Fx = 0;
|
||||
Fy = 0;
|
||||
Fz = 0;
|
||||
ROS_INFO("Load %s plugin.", _sensor->Name().c_str());
|
||||
}
|
||||
|
||||
private:
|
||||
void OnUpdate()
|
||||
{
|
||||
msgs::Contacts contacts;
|
||||
contacts = this->parentSensor->Contacts();
|
||||
count = contacts.contact_size();
|
||||
// std::cout << count <<"\n";
|
||||
for (unsigned int i = 0; i < count; ++i){
|
||||
if(contacts.contact(i).position_size() != 1){
|
||||
ROS_ERROR("Contact count isn't correct!!!!");
|
||||
}
|
||||
for (unsigned int j = 0; j < contacts.contact(i).position_size(); ++j){
|
||||
// std::cout << i <<" "<< contacts.contact(i).position_size() <<" Force:"
|
||||
// << contacts.contact(i).wrench(j).body_1_wrench().force().x() << " "
|
||||
// << contacts.contact(i).wrench(j).body_1_wrench().force().y() << " "
|
||||
// << contacts.contact(i).wrench(j).body_1_wrench().force().z() << "\n";
|
||||
Fx += contacts.contact(i).wrench(0).body_1_wrench().force().x(); // Notice: the force is in local coordinate, not in world or base coordnate.
|
||||
Fy += contacts.contact(i).wrench(0).body_1_wrench().force().y();
|
||||
Fz += contacts.contact(i).wrench(0).body_1_wrench().force().z();
|
||||
}
|
||||
}
|
||||
if(count != 0){
|
||||
force.wrench.force.x = Fx/double(count);
|
||||
force.wrench.force.y = Fy/double(count);
|
||||
force.wrench.force.z = Fz/double(count);
|
||||
count = 0;
|
||||
Fx = 0;
|
||||
Fy = 0;
|
||||
Fz = 0;
|
||||
}
|
||||
else{
|
||||
force.wrench.force.x = 0;
|
||||
force.wrench.force.y = 0;
|
||||
force.wrench.force.z = 0;
|
||||
}
|
||||
this->force_pub.publish(force);
|
||||
}
|
||||
|
||||
private:
|
||||
ros::NodeHandle* rosnode;
|
||||
ros::Publisher force_pub;
|
||||
event::ConnectionPtr update_connection;
|
||||
std::string contact_namespace;
|
||||
sensors::ContactSensorPtr parentSensor;
|
||||
geometry_msgs::WrenchStamped force;
|
||||
int count = 0;
|
||||
double Fx=0, Fy=0, Fz=0;
|
||||
};
|
||||
GZ_REGISTER_SENSOR_PLUGIN(UnitreeFootContactPlugin)
|
||||
}
|
||||
|
|
@ -0,0 +1,31 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_legged_control)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
controller_interface
|
||||
hardware_interface
|
||||
pluginlib
|
||||
roscpp
|
||||
realtime_tools
|
||||
unitree_legged_msgs
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
unitree_legged_msgs
|
||||
controller_interface
|
||||
hardware_interface
|
||||
pluginlib
|
||||
roscpp
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES ${PROJECT_NAME}
|
||||
)
|
||||
|
||||
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR})
|
||||
|
||||
link_directories($(catkin_LIB_DIRS) lib)
|
||||
|
||||
add_library( unitree_legged_control
|
||||
src/joint_controller.cpp
|
||||
)
|
||||
target_link_libraries(unitree_legged_control ${catkin_LIBRARIES} unitree_joint_control_tool)
|
|
@ -0,0 +1,73 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#ifndef _UNITREE_ROS_JOINT_CONTROLLER_H_
|
||||
#define _UNITREE_ROS_JOINT_CONTROLLER_H_
|
||||
|
||||
#include <ros/node_handle.h>
|
||||
#include <urdf/model.h>
|
||||
#include <control_toolbox/pid.h>
|
||||
#include <boost/scoped_ptr.hpp>
|
||||
#include <boost/thread/condition.hpp>
|
||||
#include <realtime_tools/realtime_publisher.h>
|
||||
#include <hardware_interface/joint_command_interface.h>
|
||||
#include <controller_interface/controller.h>
|
||||
#include <std_msgs/Float64.h>
|
||||
#include <realtime_tools/realtime_buffer.h>
|
||||
#include <controller_interface/controller.h>
|
||||
#include <hardware_interface/joint_command_interface.h>
|
||||
#include "unitree_legged_msgs/MotorCmd.h"
|
||||
#include "unitree_legged_msgs/MotorState.h"
|
||||
#include <geometry_msgs/WrenchStamped.h>
|
||||
#include "unitree_joint_control_tool.h"
|
||||
|
||||
#define PMSM (0x0A)
|
||||
#define BRAKE (0x00)
|
||||
#define PosStopF (2.146E+9f)
|
||||
#define VelStopF (16000.0f)
|
||||
|
||||
namespace unitree_legged_control
|
||||
{
|
||||
class UnitreeJointController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
|
||||
{
|
||||
private:
|
||||
hardware_interface::JointHandle joint;
|
||||
ros::Subscriber sub_cmd, sub_ft;
|
||||
// ros::Publisher pub_state;
|
||||
control_toolbox::Pid pid_controller_;
|
||||
boost::scoped_ptr<realtime_tools::RealtimePublisher<unitree_legged_msgs::MotorState> > controller_state_publisher_ ;
|
||||
|
||||
public:
|
||||
// bool start_up;
|
||||
std::string name_space;
|
||||
std::string joint_name;
|
||||
float sensor_torque;
|
||||
bool isHip, isThigh, isCalf, rqtTune;
|
||||
urdf::JointConstSharedPtr joint_urdf;
|
||||
realtime_tools::RealtimeBuffer<unitree_legged_msgs::MotorCmd> command;
|
||||
unitree_legged_msgs::MotorCmd lastCmd;
|
||||
unitree_legged_msgs::MotorState lastState;
|
||||
ServoCmd servoCmd;
|
||||
|
||||
UnitreeJointController();
|
||||
~UnitreeJointController();
|
||||
virtual bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n);
|
||||
virtual void starting(const ros::Time& time);
|
||||
virtual void update(const ros::Time& time, const ros::Duration& period);
|
||||
virtual void stopping();
|
||||
void setTorqueCB(const geometry_msgs::WrenchStampedConstPtr& msg);
|
||||
void setCommandCB(const unitree_legged_msgs::MotorCmdConstPtr& msg);
|
||||
void positionLimits(double &position);
|
||||
void velocityLimits(double &velocity);
|
||||
void effortLimits(double &effort);
|
||||
|
||||
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup = false);
|
||||
void getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup);
|
||||
void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
|
||||
|
||||
};
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,33 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
// #ifndef _UNITREE_JOINT_CONTROL_TOOL_H_
|
||||
// #define _UNITREE_JOINT_CONTROL_TOOL_H_
|
||||
#ifndef _LAIKAGO_CONTROL_TOOL_H_
|
||||
#define _LAIKAGO_CONTROL_TOOL_H_
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include <algorithm>
|
||||
#include <math.h>
|
||||
|
||||
#define posStopF (2.146E+9f) // stop position control mode
|
||||
#define velStopF (16000.0f) // stop velocity control mode
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t mode;
|
||||
double pos;
|
||||
double posStiffness;
|
||||
double vel;
|
||||
double velStiffness;
|
||||
double torque;
|
||||
} ServoCmd;
|
||||
|
||||
double clamp(double&, double, double); // eg. clamp(1.5, -1, 1) = 1
|
||||
double computeVel(double current_position, double last_position, double last_velocity, double duration); // get current velocity
|
||||
double computeTorque(double current_position, double current_velocity, ServoCmd&); // get torque
|
||||
|
||||
#endif
|
Binary file not shown.
|
@ -0,0 +1,27 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_legged_control</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The unitree_legged_control package</description>
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>controller_interface</build_depend>
|
||||
<build_depend>hardware_interface</build_depend>
|
||||
<build_depend>pluginlib</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_export_depend>controller_interface</build_export_depend>
|
||||
<build_export_depend>hardware_interface</build_export_depend>
|
||||
<build_export_depend>pluginlib</build_export_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<exec_depend>controller_interface</exec_depend>
|
||||
<exec_depend>hardware_interface</exec_depend>
|
||||
<exec_depend>pluginlib</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<depend>unitree_legged_msgs</depend>
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
<controller_interface plugin="${prefix}/unitree_controller_plugins.xml"/>
|
||||
</export>
|
||||
</package>
|
|
@ -0,0 +1,229 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
// #include "unitree_legged_control/joint_controller.h"
|
||||
#include "joint_controller.h"
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
|
||||
// #define rqtTune // use rqt or not
|
||||
|
||||
namespace unitree_legged_control
|
||||
{
|
||||
|
||||
UnitreeJointController::UnitreeJointController(){
|
||||
memset(&lastCmd, 0, sizeof(unitree_legged_msgs::MotorCmd));
|
||||
memset(&lastState, 0, sizeof(unitree_legged_msgs::MotorState));
|
||||
memset(&servoCmd, 0, sizeof(ServoCmd));
|
||||
}
|
||||
|
||||
UnitreeJointController::~UnitreeJointController(){
|
||||
sub_ft.shutdown();
|
||||
sub_cmd.shutdown();
|
||||
}
|
||||
|
||||
void UnitreeJointController::setTorqueCB(const geometry_msgs::WrenchStampedConstPtr& msg)
|
||||
{
|
||||
if(isHip) sensor_torque = msg->wrench.torque.x;
|
||||
else sensor_torque = msg->wrench.torque.y;
|
||||
// printf("sensor torque%f\n", sensor_torque);
|
||||
}
|
||||
|
||||
void UnitreeJointController::setCommandCB(const unitree_legged_msgs::MotorCmdConstPtr& msg)
|
||||
{
|
||||
lastCmd.mode = msg->mode;
|
||||
lastCmd.q = msg->q;
|
||||
lastCmd.Kp = msg->Kp;
|
||||
lastCmd.dq = msg->dq;
|
||||
lastCmd.Kd = msg->Kd;
|
||||
lastCmd.tau = msg->tau;
|
||||
// the writeFromNonRT can be used in RT, if you have the guarantee that
|
||||
// * no non-rt thread is calling the same function (we're not subscribing to ros callbacks)
|
||||
// * there is only one single rt thread
|
||||
command.writeFromNonRT(lastCmd);
|
||||
}
|
||||
|
||||
// Controller initialization in non-realtime
|
||||
bool UnitreeJointController::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
|
||||
{
|
||||
isHip = false;
|
||||
isThigh = false;
|
||||
isCalf = false;
|
||||
// rqtTune = false;
|
||||
sensor_torque = 0;
|
||||
name_space = n.getNamespace();
|
||||
if (!n.getParam("joint", joint_name)){
|
||||
ROS_ERROR("No joint given in namespace: '%s')", n.getNamespace().c_str());
|
||||
return false;
|
||||
}
|
||||
|
||||
// load pid param from ymal only if rqt need
|
||||
// if(rqtTune) {
|
||||
#ifdef rqtTune
|
||||
// Load PID Controller using gains set on parameter server
|
||||
if (!pid_controller_.init(ros::NodeHandle(n, "pid")))
|
||||
return false;
|
||||
#endif
|
||||
// }
|
||||
|
||||
urdf::Model urdf; // Get URDF info about joint
|
||||
if (!urdf.initParamWithNodeHandle("robot_description", n)){
|
||||
ROS_ERROR("Failed to parse urdf file");
|
||||
return false;
|
||||
}
|
||||
joint_urdf = urdf.getJoint(joint_name);
|
||||
if (!joint_urdf){
|
||||
ROS_ERROR("Could not find joint '%s' in urdf", joint_name.c_str());
|
||||
return false;
|
||||
}
|
||||
if(joint_name == "FR_hip_joint" || joint_name == "FL_hip_joint" || joint_name == "RR_hip_joint" || joint_name == "RL_hip_joint"){
|
||||
isHip = true;
|
||||
}
|
||||
if(joint_name == "FR_calf_joint" || joint_name == "FL_calf_joint" || joint_name == "RR_calf_joint" || joint_name == "RL_calf_joint"){
|
||||
isCalf = true;
|
||||
}
|
||||
joint = robot->getHandle(joint_name);
|
||||
|
||||
// Start command subscriber
|
||||
sub_ft = n.subscribe(name_space + "/" +"joint_wrench", 1, &UnitreeJointController::setTorqueCB, this);
|
||||
sub_cmd = n.subscribe("command", 20, &UnitreeJointController::setCommandCB, this);
|
||||
|
||||
// pub_state = n.advertise<unitree_legged_msgs::MotorState>(name_space + "/state", 20);
|
||||
// Start realtime state publisher
|
||||
controller_state_publisher_.reset(
|
||||
new realtime_tools::RealtimePublisher<unitree_legged_msgs::MotorState>(n, name_space + "/state", 1));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void UnitreeJointController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup)
|
||||
{
|
||||
pid_controller_.setGains(p,i,d,i_max,i_min,antiwindup);
|
||||
}
|
||||
|
||||
void UnitreeJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
|
||||
{
|
||||
pid_controller_.getGains(p,i,d,i_max,i_min,antiwindup);
|
||||
}
|
||||
|
||||
void UnitreeJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
|
||||
{
|
||||
bool dummy;
|
||||
pid_controller_.getGains(p,i,d,i_max,i_min,dummy);
|
||||
}
|
||||
|
||||
// Controller startup in realtime
|
||||
void UnitreeJointController::starting(const ros::Time& time)
|
||||
{
|
||||
// lastCmd.Kp = 0;
|
||||
// lastCmd.Kd = 0;
|
||||
double init_pos = joint.getPosition();
|
||||
lastCmd.q = init_pos;
|
||||
lastState.q = init_pos;
|
||||
lastCmd.dq = 0;
|
||||
lastState.dq = 0;
|
||||
lastCmd.tau = 0;
|
||||
lastState.tauEst = 0;
|
||||
command.initRT(lastCmd);
|
||||
|
||||
pid_controller_.reset();
|
||||
}
|
||||
|
||||
// Controller update loop in realtime
|
||||
void UnitreeJointController::update(const ros::Time& time, const ros::Duration& period)
|
||||
{
|
||||
double currentPos, currentVel, calcTorque;
|
||||
lastCmd = *(command.readFromRT());
|
||||
|
||||
// set command data
|
||||
if(lastCmd.mode == PMSM) {
|
||||
servoCmd.pos = lastCmd.q;
|
||||
positionLimits(servoCmd.pos);
|
||||
servoCmd.posStiffness = lastCmd.Kp;
|
||||
if(fabs(lastCmd.q - PosStopF) < 0.00001){
|
||||
servoCmd.posStiffness = 0;
|
||||
}
|
||||
servoCmd.vel = lastCmd.dq;
|
||||
velocityLimits(servoCmd.vel);
|
||||
servoCmd.velStiffness = lastCmd.Kd;
|
||||
if(fabs(lastCmd.dq - VelStopF) < 0.00001){
|
||||
servoCmd.velStiffness = 0;
|
||||
}
|
||||
servoCmd.torque = lastCmd.tau;
|
||||
effortLimits(servoCmd.torque);
|
||||
}
|
||||
if(lastCmd.mode == BRAKE) {
|
||||
servoCmd.posStiffness = 0;
|
||||
servoCmd.vel = 0;
|
||||
servoCmd.velStiffness = 20;
|
||||
servoCmd.torque = 0;
|
||||
effortLimits(servoCmd.torque);
|
||||
}
|
||||
|
||||
// } else {
|
||||
// servoCmd.posStiffness = 0;
|
||||
// servoCmd.velStiffness = 5;
|
||||
// servoCmd.torque = 0;
|
||||
// }
|
||||
|
||||
// rqt set P D gains
|
||||
// if(rqtTune) {
|
||||
#ifdef rqtTune
|
||||
double i, i_max, i_min;
|
||||
getGains(servoCmd.posStiffness,i,servoCmd.velStiffness,i_max,i_min);
|
||||
#endif
|
||||
// }
|
||||
|
||||
currentPos = joint.getPosition();
|
||||
currentVel = computeVel(currentPos, (double)lastState.q, (double)lastState.dq, period.toSec());
|
||||
calcTorque = computeTorque(currentPos, currentVel, servoCmd);
|
||||
effortLimits(calcTorque);
|
||||
|
||||
joint.setCommand(calcTorque);
|
||||
|
||||
lastState.q = currentPos;
|
||||
lastState.dq = currentVel;
|
||||
// lastState.tauEst = calcTorque;
|
||||
// lastState.tauEst = sensor_torque;
|
||||
lastState.tauEst = joint.getEffort();
|
||||
|
||||
// pub_state.publish(lastState);
|
||||
// publish state
|
||||
if (controller_state_publisher_ && controller_state_publisher_->trylock()) {
|
||||
controller_state_publisher_->msg_.q = lastState.q;
|
||||
controller_state_publisher_->msg_.dq = lastState.dq;
|
||||
controller_state_publisher_->msg_.tauEst = lastState.tauEst;
|
||||
controller_state_publisher_->unlockAndPublish();
|
||||
}
|
||||
|
||||
// printf("sensor torque%f\n", sensor_torque);
|
||||
|
||||
// if(joint_name == "wrist1_joint") printf("wrist1 setp:%f getp:%f t:%f\n", servoCmd.pos, currentPos, calcTorque);
|
||||
}
|
||||
|
||||
// Controller stopping in realtime
|
||||
void UnitreeJointController::stopping(){}
|
||||
|
||||
void UnitreeJointController::positionLimits(double &position)
|
||||
{
|
||||
if (joint_urdf->type == urdf::Joint::REVOLUTE || joint_urdf->type == urdf::Joint::PRISMATIC)
|
||||
clamp(position, joint_urdf->limits->lower, joint_urdf->limits->upper);
|
||||
}
|
||||
|
||||
void UnitreeJointController::velocityLimits(double &velocity)
|
||||
{
|
||||
if (joint_urdf->type == urdf::Joint::REVOLUTE || joint_urdf->type == urdf::Joint::PRISMATIC)
|
||||
clamp(velocity, -joint_urdf->limits->velocity, joint_urdf->limits->velocity);
|
||||
}
|
||||
|
||||
void UnitreeJointController::effortLimits(double &effort)
|
||||
{
|
||||
if (joint_urdf->type == urdf::Joint::REVOLUTE || joint_urdf->type == urdf::Joint::PRISMATIC)
|
||||
clamp(effort, -joint_urdf->limits->effort, joint_urdf->limits->effort);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
// Register controller to pluginlib
|
||||
PLUGINLIB_EXPORT_CLASS(unitree_legged_control::UnitreeJointController, controller_interface::ControllerBase);
|
|
@ -0,0 +1,8 @@
|
|||
<library path="lib/libunitree_legged_control">
|
||||
<class name="unitree_legged_control/UnitreeJointController"
|
||||
type="unitree_legged_control::UnitreeJointController"
|
||||
base_class_type="controller_interface::ControllerBase"/>
|
||||
<description>
|
||||
The unitree joint controller.
|
||||
</description>
|
||||
</library>
|
|
@ -0,0 +1,48 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_legged_msgs)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
message_generation
|
||||
std_msgs
|
||||
geometry_msgs
|
||||
sensor_msgs
|
||||
)
|
||||
|
||||
add_message_files(
|
||||
FILES
|
||||
MotorCmd.msg
|
||||
MotorState.msg
|
||||
Cartesian.msg
|
||||
IMU.msg
|
||||
LED.msg
|
||||
LowCmd.msg
|
||||
LowState.msg
|
||||
HighCmd.msg
|
||||
HighState.msg
|
||||
)
|
||||
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
std_msgs
|
||||
geometry_msgs
|
||||
sensor_msgs
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS
|
||||
message_runtime
|
||||
std_msgs
|
||||
geometry_msgs
|
||||
sensor_msgs
|
||||
)
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
# Mark topic names header files for installation
|
||||
install(
|
||||
DIRECTORY include/${PROJECT_NAME}/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
FILES_MATCHING PATTERN "*.h"
|
||||
)
|
|
@ -0,0 +1,3 @@
|
|||
float32 x
|
||||
float32 y
|
||||
float32 z
|
|
@ -0,0 +1,19 @@
|
|||
uint8 levelFlag
|
||||
uint16 commVersion
|
||||
uint16 robotID
|
||||
uint32 SN
|
||||
uint8 bandWidth
|
||||
uint8 mode
|
||||
float32 forwardSpeed
|
||||
float32 sideSpeed
|
||||
float32 rotateSpeed
|
||||
float32 bodyHeight
|
||||
float32 footRaiseHeight
|
||||
float32 yaw
|
||||
float32 pitch
|
||||
float32 roll
|
||||
LED[4] led
|
||||
uint8[40] wirelessRemote
|
||||
uint8[40] AppRemote
|
||||
uint32 reserve
|
||||
int32 crc
|
|
@ -0,0 +1,26 @@
|
|||
uint8 levelFlag
|
||||
uint16 commVersion
|
||||
uint16 robotID
|
||||
uint32 SN
|
||||
uint8 bandWidth
|
||||
uint8 mode
|
||||
IMU imu
|
||||
float32 forwardSpeed
|
||||
float32 sideSpeed
|
||||
float32 rotateSpeed
|
||||
float32 bodyHeight
|
||||
float32 updownSpeed
|
||||
float32 forwardPosition # (will be float type next version)
|
||||
float32 sidePosition # (will be float type next version)
|
||||
Cartesian[4] footPosition2Body
|
||||
Cartesian[4] footSpeed2Body
|
||||
int16[4] footForce
|
||||
int16[4] footForceEst
|
||||
uint32 tick
|
||||
uint8[40] wirelessRemote
|
||||
uint32 reserve
|
||||
uint32 crc
|
||||
|
||||
# Under are not defined in SDK yet.
|
||||
Cartesian[4] eeForce # It's a 1-DOF force in real robot, but 3-DOF is better for visualization.
|
||||
float32[12] jointP # for visualization
|
|
@ -0,0 +1,5 @@
|
|||
float32[4] quaternion
|
||||
float32[3] gyroscope
|
||||
float32[3] accelerometer
|
||||
float32[3] rpy
|
||||
int8 temperature
|
|
@ -0,0 +1,3 @@
|
|||
uint8 r
|
||||
uint8 g
|
||||
uint8 b
|
|
@ -0,0 +1,12 @@
|
|||
uint8 levelFlag
|
||||
uint16 commVersion
|
||||
uint16 robotID
|
||||
uint32 SN
|
||||
uint8 bandWidth
|
||||
MotorCmd[20] motorCmd
|
||||
LED[4] led
|
||||
uint8[40] wirelessRemote
|
||||
uint32 reserve
|
||||
uint32 crc
|
||||
|
||||
Cartesian[4] ff # will delete
|
|
@ -0,0 +1,20 @@
|
|||
uint8 levelFlag
|
||||
uint16 commVersion
|
||||
uint16 robotID
|
||||
uint32 SN
|
||||
uint8 bandWidth
|
||||
IMU imu
|
||||
MotorState[20] motorState
|
||||
int16[4] footForce # force sensors
|
||||
int16[4] footForceEst # force sensors
|
||||
uint32 tick # reference real-time from motion controller (unit: us)
|
||||
uint8[40] wirelessRemote # wireless commands
|
||||
uint32 reserve
|
||||
uint32 crc
|
||||
|
||||
|
||||
Cartesian[4] eeForceRaw
|
||||
Cartesian[4] eeForce #it's a 1-DOF force infact, but we use 3-DOF here just for visualization
|
||||
Cartesian position # will delete
|
||||
Cartesian velocity # will delete
|
||||
Cartesian velocity_w # will delete
|
|
@ -0,0 +1,7 @@
|
|||
uint8 mode # motor target mode
|
||||
float32 q # motor target position
|
||||
float32 dq # motor target velocity
|
||||
float32 tau # motor target torque
|
||||
float32 Kp # motor spring stiffness coefficient
|
||||
float32 Kd # motor damper coefficient
|
||||
uint32[3] reserve # motor target torque
|
|
@ -0,0 +1,10 @@
|
|||
uint8 mode # motor current mode
|
||||
float32 q # motor current position(rad)
|
||||
float32 dq # motor current speed(rad/s)
|
||||
float32 ddq # motor current speed(rad/s)
|
||||
float32 tauEst # current estimated output torque(N*m)
|
||||
float32 q_raw # motor current position(rad)
|
||||
float32 dq_raw # motor current speed(rad/s)
|
||||
float32 ddq_raw # motor current speed(rad/s)
|
||||
int8 temperature # motor temperature(slow conduction of temperature leads to lag)
|
||||
uint32[2] reserve
|
|
@ -0,0 +1,19 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<package format="2">
|
||||
<name>unitree_legged_msgs</name>
|
||||
<version>0.0.0</version>
|
||||
<description>
|
||||
The test messgaes package.
|
||||
</description>
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<depend>message_runtime</depend>
|
||||
<depend>message_generation</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>geometry_msgs</depend>
|
||||
<depend>sensor_msgs</depend>
|
||||
|
||||
</package>
|
|
@ -0,0 +1,48 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(unitree_legged_real)
|
||||
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
controller_manager
|
||||
roscpp
|
||||
tf
|
||||
geometry_msgs
|
||||
unitree_legged_msgs
|
||||
)
|
||||
|
||||
find_package(Eigen3 REQUIRED)
|
||||
|
||||
catkin_package(
|
||||
)
|
||||
|
||||
include_directories(
|
||||
# /home/unitree/unitree_legged_sdk/include
|
||||
include
|
||||
${Boost_INCLUDE_DIR}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${EIGEN3_INCLUDE_DIR}
|
||||
# /home/bian/unitree_legged_sdk/include/unitree_legged_sdk
|
||||
$ENV{UNITREE_LEGGED_SDK_PATH}/include
|
||||
)
|
||||
|
||||
link_directories($ENV{UNITREE_LEGGED_SDK_PATH}/lib)
|
||||
string(CONCAT LEGGED_SDK_NAME libunitree_legged_sdk_$ENV{UNITREE_PLATFORM}.so)
|
||||
set(EXTRA_LIBS ${LEGGED_SDK_NAME} lcm)
|
||||
|
||||
set(CMAKE_CXX_FLAGS "-O3")
|
||||
|
||||
add_executable(position_lcm src/exe/position_mode.cpp)
|
||||
target_link_libraries(position_lcm ${EXTRA_LIBS} ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(velocity_lcm src/exe/velocity_mode.cpp)
|
||||
target_link_libraries(velocity_lcm ${EXTRA_LIBS} ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(torque_lcm src/exe/torque_mode.cpp)
|
||||
target_link_libraries(torque_lcm ${EXTRA_LIBS} ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(walk_lcm src/exe/walk_mode.cpp)
|
||||
target_link_libraries(walk_lcm ${EXTRA_LIBS} ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(lcm_server $ENV{UNITREE_LEGGED_SDK_PATH}/examples/lcm_server.cpp)
|
||||
target_link_libraries(lcm_server ${EXTRA_LIBS} ${catkin_LIBRARIES})
|
|
@ -0,0 +1,187 @@
|
|||
/*****************************************************************
|
||||
Copyright (c) 2020, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
******************************************************************/
|
||||
|
||||
#ifndef _CONVERT_H_
|
||||
#define _CONVERT_H_
|
||||
|
||||
#include "unitree_legged_sdk/unitree_legged_sdk.h"
|
||||
#include <unitree_legged_msgs/LowCmd.h>
|
||||
#include <unitree_legged_msgs/LowState.h>
|
||||
#include <unitree_legged_msgs/HighCmd.h>
|
||||
#include <unitree_legged_msgs/HighState.h>
|
||||
#include <unitree_legged_msgs/MotorCmd.h>
|
||||
#include <unitree_legged_msgs/MotorState.h>
|
||||
#include <unitree_legged_msgs/IMU.h>
|
||||
|
||||
|
||||
unitree_legged_msgs::IMU ToRos(UNITREE_LEGGED_SDK::IMU& lcm)
|
||||
{
|
||||
unitree_legged_msgs::IMU ros;
|
||||
ros.quaternion[0] = lcm.quaternion[0];
|
||||
ros.quaternion[1] = lcm.quaternion[1];
|
||||
ros.quaternion[2] = lcm.quaternion[2];
|
||||
ros.quaternion[3] = lcm.quaternion[3];
|
||||
ros.gyroscope[0] = lcm.gyroscope[0];
|
||||
ros.gyroscope[1] = lcm.gyroscope[1];
|
||||
ros.gyroscope[2] = lcm.gyroscope[2];
|
||||
ros.accelerometer[0] = lcm.accelerometer[0];
|
||||
ros.accelerometer[1] = lcm.accelerometer[1];
|
||||
ros.accelerometer[2] = lcm.accelerometer[2];
|
||||
ros.rpy[0] = lcm.rpy[0];
|
||||
ros.rpy[1] = lcm.rpy[1];
|
||||
ros.rpy[2] = lcm.rpy[2];
|
||||
ros.temperature = lcm.temperature;
|
||||
return ros;
|
||||
}
|
||||
|
||||
unitree_legged_msgs::MotorState ToRos(UNITREE_LEGGED_SDK::MotorState& lcm)
|
||||
{
|
||||
unitree_legged_msgs::MotorState ros;
|
||||
ros.mode = lcm.mode;
|
||||
ros.q = lcm.q;
|
||||
ros.dq = lcm.dq;
|
||||
ros.ddq = lcm.ddq;
|
||||
ros.tauEst = lcm.tauEst;
|
||||
ros.q_raw = lcm.q_raw;
|
||||
ros.dq_raw = lcm.dq_raw;
|
||||
ros.ddq_raw = lcm.ddq_raw;
|
||||
ros.temperature = lcm.temperature;
|
||||
ros.reserve[0] = lcm.reserve[0];
|
||||
ros.reserve[1] = lcm.reserve[1];
|
||||
return ros;
|
||||
}
|
||||
|
||||
UNITREE_LEGGED_SDK::MotorCmd ToLcm(unitree_legged_msgs::MotorCmd& ros)
|
||||
{
|
||||
UNITREE_LEGGED_SDK::MotorCmd lcm;
|
||||
lcm.mode = ros.mode;
|
||||
lcm.q = ros.q;
|
||||
lcm.dq = ros.dq;
|
||||
lcm.tau = ros.tau;
|
||||
lcm.Kp = ros.Kp;
|
||||
lcm.Kd = ros.Kd;
|
||||
lcm.reserve[0] = ros.reserve[0];
|
||||
lcm.reserve[1] = ros.reserve[1];
|
||||
lcm.reserve[2] = ros.reserve[2];
|
||||
return lcm;
|
||||
}
|
||||
|
||||
unitree_legged_msgs::LowState ToRos(UNITREE_LEGGED_SDK::LowState& lcm)
|
||||
{
|
||||
unitree_legged_msgs::LowState ros;
|
||||
ros.levelFlag = lcm.levelFlag;
|
||||
ros.commVersion = lcm.commVersion;
|
||||
ros.robotID = lcm.robotID;
|
||||
ros.SN = lcm.SN;
|
||||
ros.bandWidth = lcm.bandWidth;
|
||||
ros.imu = ToRos(lcm.imu);
|
||||
for(int i = 0; i<20; i++){
|
||||
ros.motorState[i] = ToRos(lcm.motorState[i]);
|
||||
}
|
||||
for(int i = 0; i<4; i++){
|
||||
ros.footForce[i] = lcm.footForce[i];
|
||||
ros.footForceEst[i] = lcm.footForceEst[i];
|
||||
}
|
||||
ros.tick = lcm.tick;
|
||||
for(int i = 0; i<40; i++){
|
||||
ros.wirelessRemote[i] = lcm.wirelessRemote[i];
|
||||
}
|
||||
ros.reserve = lcm.reserve;
|
||||
ros.crc = lcm.crc;
|
||||
return ros;
|
||||
}
|
||||
|
||||
UNITREE_LEGGED_SDK::LowCmd ToLcm(unitree_legged_msgs::LowCmd& ros)
|
||||
{
|
||||
UNITREE_LEGGED_SDK::LowCmd lcm;
|
||||
lcm.levelFlag = ros.levelFlag;
|
||||
lcm.commVersion = ros.commVersion;
|
||||
lcm.robotID = ros.robotID;
|
||||
lcm.SN = ros.SN;
|
||||
lcm.bandWidth = ros.bandWidth;
|
||||
for(int i = 0; i<20; i++){
|
||||
lcm.motorCmd[i] = ToLcm(ros.motorCmd[i]);
|
||||
}
|
||||
for(int i = 0; i<4; i++){
|
||||
lcm.led[i].r = ros.led[i].r;
|
||||
lcm.led[i].g = ros.led[i].g;
|
||||
lcm.led[i].b = ros.led[i].b;
|
||||
}
|
||||
for(int i = 0; i<40; i++){
|
||||
lcm.wirelessRemote[i] = ros.wirelessRemote[i];
|
||||
}
|
||||
lcm.reserve = ros.reserve;
|
||||
lcm.crc = ros.crc;
|
||||
return lcm;
|
||||
}
|
||||
|
||||
unitree_legged_msgs::HighState ToRos(UNITREE_LEGGED_SDK::HighState& lcm)
|
||||
{
|
||||
unitree_legged_msgs::HighState ros;
|
||||
ros.levelFlag = lcm.levelFlag;
|
||||
ros.commVersion = lcm.commVersion;
|
||||
ros.robotID = lcm.robotID;
|
||||
ros.SN = lcm.SN;
|
||||
ros.bandWidth = lcm.bandWidth;
|
||||
ros.mode = lcm.mode;
|
||||
ros.imu = ToRos(lcm.imu);
|
||||
ros.forwardSpeed = lcm.forwardSpeed;
|
||||
ros.sideSpeed = lcm.sideSpeed;
|
||||
ros.rotateSpeed = lcm.rotateSpeed;
|
||||
ros.bodyHeight = lcm.bodyHeight;
|
||||
ros.updownSpeed = lcm.updownSpeed;
|
||||
ros.forwardPosition = lcm.forwardPosition;
|
||||
ros.sidePosition = lcm.sidePosition;
|
||||
for(int i = 0; i<4; i++){
|
||||
ros.footPosition2Body[i].x = lcm.footPosition2Body[i].x;
|
||||
ros.footPosition2Body[i].y = lcm.footPosition2Body[i].y;
|
||||
ros.footPosition2Body[i].z = lcm.footPosition2Body[i].z;
|
||||
ros.footSpeed2Body[i].x = lcm.footSpeed2Body[i].x;
|
||||
ros.footSpeed2Body[i].y = lcm.footSpeed2Body[i].y;
|
||||
ros.footSpeed2Body[i].z = lcm.footSpeed2Body[i].z;
|
||||
ros.footForce[i] = lcm.footForce[i];
|
||||
ros.footForceEst[i] = lcm.footForceEst[i];
|
||||
}
|
||||
ros.tick = lcm.tick;
|
||||
for(int i = 0; i<40; i++){
|
||||
ros.wirelessRemote[i] = lcm.wirelessRemote[i];
|
||||
}
|
||||
ros.reserve = lcm.reserve;
|
||||
ros.crc = lcm.crc;
|
||||
return ros;
|
||||
}
|
||||
|
||||
UNITREE_LEGGED_SDK::HighCmd ToLcm(unitree_legged_msgs::HighCmd& ros)
|
||||
{
|
||||
UNITREE_LEGGED_SDK::HighCmd lcm;
|
||||
lcm.levelFlag = ros.levelFlag;
|
||||
lcm.commVersion = ros.commVersion;
|
||||
lcm.robotID = ros.robotID;
|
||||
lcm.SN = ros.SN;
|
||||
lcm.bandWidth = ros.bandWidth;
|
||||
lcm.mode = ros.mode;
|
||||
lcm.forwardSpeed = ros.forwardSpeed;
|
||||
lcm.sideSpeed = ros.sideSpeed;
|
||||
lcm.rotateSpeed = ros.rotateSpeed;
|
||||
lcm.bodyHeight = ros.bodyHeight;
|
||||
lcm.footRaiseHeight = ros.footRaiseHeight;
|
||||
lcm.yaw = ros.yaw;
|
||||
lcm.pitch = ros.pitch;
|
||||
lcm.roll = ros.roll;
|
||||
for(int i = 0; i<4; i++){
|
||||
lcm.led[i].r = ros.led[i].r;
|
||||
lcm.led[i].g = ros.led[i].g;
|
||||
lcm.led[i].b = ros.led[i].b;
|
||||
}
|
||||
for(int i = 0; i<40; i++){
|
||||
lcm.wirelessRemote[i] = ros.wirelessRemote[i];
|
||||
lcm.AppRemote[i] = ros.AppRemote[i];
|
||||
}
|
||||
lcm.reserve = ros.reserve;
|
||||
lcm.crc = ros.crc;
|
||||
return lcm;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,11 @@
|
|||
<launch>
|
||||
<arg name="rname" default="a1"/>
|
||||
<arg name="ctrl_level" default="highlevel"/>
|
||||
|
||||
<node pkg="unitree_legged_real" type="lcm_server" name="node_lcm_server"
|
||||
respawn="false" output="screen" args="$(arg rname) $(arg ctrl_level)" />
|
||||
|
||||
<param name="robot_name" value="$(arg rname)"/>
|
||||
<param name="control_level" value="$(arg ctrl_level)"/>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,20 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>unitree_legged_real</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The unitree_legged_real 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>
|
||||
<depend>unitree_legged_msgs</depend>
|
||||
<depend>eigen</depend>
|
||||
|
||||
</package>
|
|
@ -0,0 +1,159 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <unitree_legged_msgs/LowCmd.h>
|
||||
#include <unitree_legged_msgs/LowState.h>
|
||||
#include "unitree_legged_sdk/unitree_legged_sdk.h"
|
||||
#include "convert.h"
|
||||
|
||||
using namespace UNITREE_LEGGED_SDK;
|
||||
|
||||
class Custom
|
||||
{
|
||||
public:
|
||||
Custom() {}
|
||||
void LCMRecv();
|
||||
|
||||
LCM roslcm;
|
||||
};
|
||||
|
||||
void Custom::LCMRecv()
|
||||
{
|
||||
roslcm.Recv();
|
||||
}
|
||||
|
||||
double jointLinearInterpolation(double initPos, double targetPos, double rate)
|
||||
{
|
||||
double p;
|
||||
rate = std::min(std::max(rate, 0.0), 1.0);
|
||||
p = initPos*(1-rate) + targetPos*rate;
|
||||
return p;
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
std::cout << "WARNING: Control level is set to LOW-level." << std::endl
|
||||
<< "Make sure the robot is hung up." << std::endl
|
||||
<< "Press Enter to continue..." << std::endl;
|
||||
std::cin.ignore();
|
||||
|
||||
ros::init(argc, argv, "position_ros_mode");
|
||||
ros::NodeHandle n;
|
||||
ros::Rate loop_rate(500);
|
||||
|
||||
Custom custom;
|
||||
SetLevel(LOWLEVEL); // must have this
|
||||
long motiontime = 0;
|
||||
int rate_count = 0;
|
||||
int sin_count = 0;
|
||||
float qInit[3]={0};
|
||||
float qDes[3]={0};
|
||||
float sin_mid_q[3] = {0.0, 1.2, -2.0};
|
||||
float Kp[3] = {0};
|
||||
float Kd[3] = {0};
|
||||
LowCmd SendLowLCM = {0};
|
||||
LowState RecvLowLCM = {0};
|
||||
unitree_legged_msgs::LowCmd SendLowROS;
|
||||
unitree_legged_msgs::LowState RecvLowROS;
|
||||
bool initiated_flag = false; // initiate need time
|
||||
int count = 0;
|
||||
|
||||
custom.roslcm.SubscribeState();
|
||||
|
||||
LoopFunc loop_lcm("LCM_Recv", 0.002, 3, boost::bind(&Custom::LCMRecv, &custom));
|
||||
loop_lcm.start();
|
||||
|
||||
SendLowROS.levelFlag = LOWLEVEL;
|
||||
for(int i = 0; i<12; i++){
|
||||
SendLowROS.motorCmd[i].mode = 0x0A; // motor switch to servo (PMSM) mode
|
||||
SendLowROS.motorCmd[i].q = PosStopF; // 禁止位置环
|
||||
SendLowROS.motorCmd[i].Kp = 0;
|
||||
SendLowROS.motorCmd[i].dq = VelStopF; // 禁止速度环
|
||||
SendLowROS.motorCmd[i].Kd = 0;
|
||||
SendLowROS.motorCmd[i].tau = 0;
|
||||
}
|
||||
|
||||
while (ros::ok()){
|
||||
custom.roslcm.Get(RecvLowLCM);
|
||||
RecvLowROS = ToRos(RecvLowLCM);
|
||||
|
||||
if(initiated_flag == true){
|
||||
motiontime++;
|
||||
|
||||
SendLowROS.motorCmd[FR_0].tau = -0.65f;
|
||||
SendLowROS.motorCmd[FL_0].tau = +0.65f;
|
||||
SendLowROS.motorCmd[RR_0].tau = -0.65f;
|
||||
SendLowROS.motorCmd[RL_0].tau = +0.65f;
|
||||
|
||||
// printf("%d\n", motiontime);
|
||||
// printf("%d %f %f %f\n", FR_0, RecvLowROS.motorState[FR_0].q, RecvLowROS.motorState[FR_1].q, RecvLowROS.motorState[FR_2].q);
|
||||
// printf("%f %f \n", RecvLowROS.motorState[FR_0].mode, RecvLowROS.motorState[FR_1].mode);
|
||||
if( motiontime >= 0){
|
||||
// first, get record initial position
|
||||
// if( motiontime >= 100 && motiontime < 500){
|
||||
if( motiontime >= 0 && motiontime < 10){
|
||||
qInit[0] = RecvLowROS.motorState[FR_0].q;
|
||||
qInit[1] = RecvLowROS.motorState[FR_1].q;
|
||||
qInit[2] = RecvLowROS.motorState[FR_2].q;
|
||||
}
|
||||
if( motiontime >= 10 && motiontime < 400){
|
||||
// printf("%f %f %f\n", );
|
||||
rate_count++;
|
||||
double rate = rate_count/200.0; // needs count to 200
|
||||
Kp[0] = 5.0; Kp[1] = 5.0; Kp[2] = 5.0;
|
||||
Kd[0] = 1.0; Kd[1] = 1.0; Kd[2] = 1.0;
|
||||
|
||||
qDes[0] = jointLinearInterpolation(qInit[0], sin_mid_q[0], rate);
|
||||
qDes[1] = jointLinearInterpolation(qInit[1], sin_mid_q[1], rate);
|
||||
qDes[2] = jointLinearInterpolation(qInit[2], sin_mid_q[2], rate);
|
||||
}
|
||||
double sin_joint1, sin_joint2;
|
||||
// last, do sine wave
|
||||
if( motiontime >= 1700){
|
||||
sin_count++;
|
||||
sin_joint1 = 0.6 * sin(3*M_PI*sin_count/1000.0);
|
||||
sin_joint2 = -0.6 * sin(1.8*M_PI*sin_count/1000.0);
|
||||
qDes[0] = sin_mid_q[0];
|
||||
qDes[1] = sin_mid_q[1];
|
||||
qDes[2] = sin_mid_q[2] + sin_joint2;
|
||||
// qDes[2] = sin_mid_q[2];
|
||||
}
|
||||
|
||||
SendLowROS.motorCmd[FR_0].q = qDes[0];
|
||||
SendLowROS.motorCmd[FR_0].dq = 0;
|
||||
SendLowROS.motorCmd[FR_0].Kp = Kp[0];
|
||||
SendLowROS.motorCmd[FR_0].Kd = Kd[0];
|
||||
SendLowROS.motorCmd[FR_0].tau = -0.65f;
|
||||
|
||||
SendLowROS.motorCmd[FR_1].q = qDes[1];
|
||||
SendLowROS.motorCmd[FR_1].dq = 0;
|
||||
SendLowROS.motorCmd[FR_1].Kp = Kp[1];
|
||||
SendLowROS.motorCmd[FR_1].Kd = Kd[1];
|
||||
SendLowROS.motorCmd[FR_1].tau = 0.0f;
|
||||
|
||||
SendLowROS.motorCmd[FR_2].q = qDes[2];
|
||||
SendLowROS.motorCmd[FR_2].dq = 0;
|
||||
SendLowROS.motorCmd[FR_2].Kp = Kp[2];
|
||||
SendLowROS.motorCmd[FR_2].Kd = Kd[2];
|
||||
SendLowROS.motorCmd[FR_2].tau = 0.0f;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
SendLowLCM = ToLcm(SendLowROS);
|
||||
custom.roslcm.Send(SendLowLCM);
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
|
||||
count++;
|
||||
if(count > 10){
|
||||
count = 10;
|
||||
initiated_flag = true;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,94 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <pthread.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/thread/mutex.hpp>
|
||||
#include <unitree_legged_msgs/LowCmd.h>
|
||||
#include <unitree_legged_msgs/LowState.h>
|
||||
#include "unitree_legged_sdk/unitree_legged_sdk.h"
|
||||
#include "convert.h"
|
||||
|
||||
using namespace UNITREE_LEGGED_SDK;
|
||||
|
||||
void* update_loop(void* param)
|
||||
{
|
||||
LCM *data = (LCM *)param;
|
||||
while(ros::ok){
|
||||
data->Recv();
|
||||
usleep(2000);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
std::cout << "WARNING: Control level is set to LOW-level." << std::endl
|
||||
<< "Make sure the robot is hung up." << std::endl
|
||||
<< "Press Enter to continue..." << std::endl;
|
||||
std::cin.ignore();
|
||||
|
||||
ros::init(argc, argv, "torque_ros_mode");
|
||||
ros::NodeHandle n;
|
||||
ros::Rate loop_rate(500);
|
||||
|
||||
std::string robot_name;
|
||||
LeggedType rname;
|
||||
ros::param::get("/robot_name", robot_name);
|
||||
if(strcasecmp(robot_name.c_str(), "A1") == 0)
|
||||
rname = LeggedType::A1;
|
||||
else if(strcasecmp(robot_name.c_str(), "Aliengo") == 0)
|
||||
rname = LeggedType::Aliengo;
|
||||
|
||||
Control control(rname, LOWLEVEL);
|
||||
|
||||
long motiontime=0;
|
||||
float torque = 0;
|
||||
LowCmd SendLowLCM = {0};
|
||||
LowState RecvLowLCM = {0};
|
||||
unitree_legged_msgs::LowCmd SendLowROS;
|
||||
unitree_legged_msgs::LowState RecvLowROS;
|
||||
LCM roslcm;
|
||||
|
||||
roslcm.SubscribeState();
|
||||
|
||||
pthread_t tid;
|
||||
pthread_create(&tid, NULL, update_loop, &roslcm);
|
||||
|
||||
SendLowROS.levelFlag = LOWLEVEL;
|
||||
for(int i = 0; i<12; i++){
|
||||
SendLowROS.motorCmd[i].mode = 0x0A; // motor switch to servo (PMSM) mode
|
||||
}
|
||||
|
||||
while (ros::ok()){
|
||||
motiontime++;
|
||||
roslcm.Get(RecvLowLCM);
|
||||
RecvLowROS = ToRos(RecvLowLCM);
|
||||
printf("FL_1 position: %f\n", RecvLowROS.motorState[FL_1].q);
|
||||
|
||||
// gravity compensation
|
||||
SendLowROS.motorCmd[FR_0].tau = -0.65f;
|
||||
SendLowROS.motorCmd[FL_0].tau = +0.65f;
|
||||
SendLowROS.motorCmd[RR_0].tau = -0.65f;
|
||||
SendLowROS.motorCmd[RL_0].tau = +0.65f;
|
||||
|
||||
if( motiontime >= 500){
|
||||
torque = (0 - RecvLowROS.motorState[FL_1].q)*10.0f + (0 - RecvLowROS.motorState[FL_1].dq)*1.0f;
|
||||
if(torque > 5.0f) torque = 5.0f;
|
||||
if(torque < -5.0f) torque = -5.0f;
|
||||
|
||||
SendLowROS.motorCmd[FL_1].q = PosStopF;
|
||||
SendLowROS.motorCmd[FL_1].dq = VelStopF;
|
||||
SendLowROS.motorCmd[FL_1].Kp = 0;
|
||||
SendLowROS.motorCmd[FL_1].Kd = 0;
|
||||
SendLowROS.motorCmd[FL_1].tau = torque;
|
||||
}
|
||||
SendLowLCM = ToLcm(SendLowROS);
|
||||
roslcm.Send(SendLowLCM);
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
}
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,96 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <string>
|
||||
#include <pthread.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/thread/mutex.hpp>
|
||||
#include <unitree_legged_msgs/LowCmd.h>
|
||||
#include <unitree_legged_msgs/LowState.h>
|
||||
#include "unitree_legged_sdk/unitree_legged_sdk.h"
|
||||
#include "convert.h"
|
||||
|
||||
using namespace UNITREE_LEGGED_SDK;
|
||||
|
||||
void* update_loop(void* param)
|
||||
{
|
||||
LCM *data = (LCM *)param;
|
||||
while(ros::ok){
|
||||
data->Recv();
|
||||
usleep(2000);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
std::cout << "WARNING: Control level is set to LOW-level." << std::endl
|
||||
<< "Make sure the robot is hung up." << std::endl
|
||||
<< "Press Enter to continue..." << std::endl;
|
||||
std::cin.ignore();
|
||||
|
||||
ros::init(argc, argv, "velocity_ros_mode");
|
||||
ros::NodeHandle n;
|
||||
ros::Rate loop_rate(500);
|
||||
|
||||
std::string robot_name;
|
||||
LeggedType rname;
|
||||
ros::param::get("/robot_name", robot_name);
|
||||
if(strcasecmp(robot_name.c_str(), "A1") == 0)
|
||||
rname = LeggedType::A1;
|
||||
else if(strcasecmp(robot_name.c_str(), "Aliengo") == 0)
|
||||
rname = LeggedType::Aliengo;
|
||||
|
||||
Control control(rname, LOWLEVEL);
|
||||
|
||||
long motiontime=0;
|
||||
float Kv = 1.5;
|
||||
float speed = 0;
|
||||
unsigned long int Tpi =0;
|
||||
LowCmd SendLowLCM = {0};
|
||||
LowState RecvLowLCM = {0};
|
||||
unitree_legged_msgs::LowCmd SendLowROS;
|
||||
unitree_legged_msgs::LowState RecvLowROS;
|
||||
LCM roslcm;
|
||||
|
||||
roslcm.SubscribeState();
|
||||
|
||||
pthread_t tid;
|
||||
pthread_create(&tid, NULL, update_loop, &roslcm);
|
||||
|
||||
SendLowROS.levelFlag = LOWLEVEL;
|
||||
for(int i = 0; i<12; i++){
|
||||
SendLowROS.motorCmd[i].mode = 0x0A; // motor switch to servo (PMSM) mode
|
||||
}
|
||||
|
||||
while (ros::ok()){
|
||||
motiontime++;
|
||||
roslcm.Get(RecvLowLCM);
|
||||
RecvLowROS = ToRos(RecvLowLCM);
|
||||
printf("motorState[FL_2] velocity: %f\n", RecvLowROS.motorState[FL_2].dq);
|
||||
|
||||
// gravity compensation
|
||||
SendLowROS.motorCmd[FR_0].tau = -0.65f;
|
||||
SendLowROS.motorCmd[FL_0].tau = +0.65f;
|
||||
SendLowROS.motorCmd[RR_0].tau = -0.65f;
|
||||
SendLowROS.motorCmd[RL_0].tau = +0.65f;
|
||||
|
||||
if( motiontime >= 500){
|
||||
SendLowROS.motorCmd[FL_2].q = PosStopF;
|
||||
SendLowROS.motorCmd[FL_2].dq = speed;
|
||||
SendLowROS.motorCmd[FL_2].Kp = 0;
|
||||
SendLowROS.motorCmd[FL_2].Kd = Kv;
|
||||
SendLowROS.motorCmd[FL_2].tau = 0.0f;
|
||||
Tpi++;
|
||||
// try 1 or 3
|
||||
speed = 3 * sin(4*M_PI*Tpi/1000.0);
|
||||
}
|
||||
SendLowLCM = ToLcm(SendLowROS);
|
||||
roslcm.Send(SendLowLCM);
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
}
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,131 @@
|
|||
/************************************************************************
|
||||
Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved.
|
||||
Use of this source code is governed by the MPL-2.0 license, see LICENSE.
|
||||
************************************************************************/
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <pthread.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/thread/mutex.hpp>
|
||||
#include <unitree_legged_msgs/HighCmd.h>
|
||||
#include <unitree_legged_msgs/HighState.h>
|
||||
#include "unitree_legged_sdk/unitree_legged_sdk.h"
|
||||
#include "convert.h"
|
||||
|
||||
using namespace UNITREE_LEGGED_SDK;
|
||||
|
||||
void* update_loop(void* param)
|
||||
{
|
||||
LCM *data = (LCM *)param;
|
||||
while(ros::ok){
|
||||
data->Recv();
|
||||
usleep(2000);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
std::cout << "WARNING: Control level is set to HIGH-level." << std::endl
|
||||
<< "Make sure the robot is standing on the ground." << std::endl
|
||||
<< "Press Enter to continue..." << std::endl;
|
||||
std::cin.ignore();
|
||||
|
||||
ros::init(argc, argv, "walk_ros_mode");
|
||||
ros::NodeHandle n;
|
||||
ros::Rate loop_rate(500);
|
||||
|
||||
// SetLevel(HIGHLEVEL);
|
||||
long motiontime = 0;
|
||||
HighCmd SendHighLCM = {0};
|
||||
HighState RecvHighLCM = {0};
|
||||
unitree_legged_msgs::HighCmd SendHighROS;
|
||||
unitree_legged_msgs::HighState RecvHighROS;
|
||||
LCM roslcm;
|
||||
|
||||
roslcm.SubscribeState();
|
||||
|
||||
pthread_t tid;
|
||||
pthread_create(&tid, NULL, update_loop, &roslcm);
|
||||
|
||||
while (ros::ok()){
|
||||
motiontime = motiontime+2;
|
||||
roslcm.Get(RecvHighLCM);
|
||||
RecvHighROS = ToRos(RecvHighLCM);
|
||||
// printf("%f\n", RecvHighROS.forwardSpeed);
|
||||
|
||||
SendHighROS.forwardSpeed = 0.0f;
|
||||
SendHighROS.sideSpeed = 0.0f;
|
||||
SendHighROS.rotateSpeed = 0.0f;
|
||||
SendHighROS.bodyHeight = 0.0f;
|
||||
|
||||
SendHighROS.mode = 0;
|
||||
SendHighROS.roll = 0;
|
||||
SendHighROS.pitch = 0;
|
||||
SendHighROS.yaw = 0;
|
||||
|
||||
if(motiontime>1000 && motiontime<1500){
|
||||
SendHighROS.mode = 1;
|
||||
// SendHighROS.roll = 0.3f;
|
||||
}
|
||||
|
||||
if(motiontime>1500 && motiontime<2000){
|
||||
SendHighROS.mode = 1;
|
||||
SendHighROS.pitch = 0.3f;
|
||||
}
|
||||
|
||||
if(motiontime>2000 && motiontime<2500){
|
||||
SendHighROS.mode = 1;
|
||||
SendHighROS.yaw = 0.2f;
|
||||
}
|
||||
|
||||
if(motiontime>2500 && motiontime<3000){
|
||||
SendHighROS.mode = 1;
|
||||
SendHighROS.bodyHeight = -0.3f;
|
||||
}
|
||||
|
||||
if(motiontime>3000 && motiontime<3500){
|
||||
SendHighROS.mode = 1;
|
||||
SendHighROS.bodyHeight = 0.3f;
|
||||
}
|
||||
|
||||
if(motiontime>3500 && motiontime<4000){
|
||||
SendHighROS.mode = 1;
|
||||
SendHighROS.bodyHeight = 0.0f;
|
||||
}
|
||||
|
||||
if(motiontime>4000 && motiontime<5000){
|
||||
SendHighROS.mode = 2;
|
||||
}
|
||||
|
||||
if(motiontime>5000 && motiontime<8500){
|
||||
SendHighROS.mode = 2;
|
||||
SendHighROS.forwardSpeed = 0.1f; // -1 ~ +1
|
||||
}
|
||||
|
||||
if(motiontime>8500 && motiontime<12000){
|
||||
SendHighROS.mode = 2;
|
||||
SendHighROS.forwardSpeed = -0.2f; // -1 ~ +1
|
||||
}
|
||||
|
||||
if(motiontime>12000 && motiontime<16000){
|
||||
SendHighROS.mode = 2;
|
||||
SendHighROS.rotateSpeed = 0.1f; // turn
|
||||
}
|
||||
|
||||
if(motiontime>16000 && motiontime<20000){
|
||||
SendHighROS.mode = 2;
|
||||
SendHighROS.rotateSpeed = -0.1f; // turn
|
||||
}
|
||||
|
||||
if(motiontime>20000 && motiontime<21000){
|
||||
SendHighROS.mode = 1;
|
||||
}
|
||||
|
||||
SendHighLCM = ToLcm(SendHighROS);
|
||||
roslcm.Send(SendHighLCM);
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,4 @@
|
|||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(unitree_ros)
|
||||
find_package(catkin REQUIRED)
|
||||
catkin_metapackage()
|
|
@ -0,0 +1,14 @@
|
|||
<?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>
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue