ocs2 controller dependencies fix

This commit is contained in:
Huang Zhenbiao 2025-01-16 11:06:27 +08:00
parent 8e05408d7b
commit 2a6af12ea7
16 changed files with 823 additions and 260 deletions

View File

@ -16,7 +16,7 @@ Todo List:
- [x] [Contact Sensor Simulation](https://github.com/legubiao/unitree_mujoco) - [x] [Contact Sensor Simulation](https://github.com/legubiao/unitree_mujoco)
- [x] [OCS2 Quadruped Control](controllers/ocs2_quadruped_controller) - [x] [OCS2 Quadruped Control](controllers/ocs2_quadruped_controller)
- [x] [Learning-based Controller](controllers/rl_quadruped_controller/) - [x] [Learning-based Controller](controllers/rl_quadruped_controller/)
- [ ] Fully understand the RL Workflow - [x] Fully understand the RL Workflow
- [x] ROS2 Humble Gazebo Classic Support - [x] ROS2 Humble Gazebo Classic Support
Video for Unitree Guide Controller: Video for Unitree Guide Controller:

View File

@ -9,9 +9,7 @@
#include <ocs2_centroidal_model/CentroidalModelPinocchioMapping.h> #include <ocs2_centroidal_model/CentroidalModelPinocchioMapping.h>
#include <ocs2_pinocchio_interface/PinocchioEndEffectorKinematics.h> #include <ocs2_pinocchio_interface/PinocchioEndEffectorKinematics.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/transform_broadcaster.h> #include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
namespace ocs2::legged_robot { namespace ocs2::legged_robot {
class KalmanFilterEstimate final : public StateEstimateBase { class KalmanFilterEstimate final : public StateEstimateBase {

View File

@ -7,7 +7,6 @@
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp> #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp> #include <nav_msgs/msg/odometry.hpp>
#include <realtime_tools/realtime_tools/realtime_publisher.h>
#include <ocs2_centroidal_model/CentroidalModelInfo.h> #include <ocs2_centroidal_model/CentroidalModelInfo.h>
#include <ocs2_legged_robot/common/ModelSettings.h> #include <ocs2_legged_robot/common/ModelSettings.h>

View File

@ -22,13 +22,18 @@ ros2 launch anymal_c_description visualize.launch.py
## Launch ROS2 Control ## Launch ROS2 Control
### Mujoco Simulator ### Mujoco Simulator
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller mujoco.launch.py pkg_description:=anymal_c_description
```
* OCS2 Quadruped Controller * OCS2 Quadruped Controller
```bash ```bash
source ~/ros2_ws/install/setup.bash source ~/ros2_ws/install/setup.bash
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=anymal_c_description ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=anymal_c_description
``` ```
* Legged Gym Controller * Legged Gym Controller
```bash ```bash
source ~/ros2_ws/install/setup.bash source ~/ros2_ws/install/setup.bash
ros2 launch anymal_c_description rl_control.launch.py ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=anymal_c_description
``` ```

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 500 # Hz update_rate: 200 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -17,13 +17,91 @@ controller_manager:
type: ocs2_quadruped_controller/Ocs2QuadrupedController type: ocs2_quadruped_controller/Ocs2QuadrupedController
rl_quadruped_controller: rl_quadruped_controller:
type: LH_quadruped_controller/LeggedGymController type: rl_quadruped_controller/LeggedGymController
imu_sensor_broadcaster: imu_sensor_broadcaster:
ros__parameters: ros__parameters:
sensor_name: "imu_sensor" sensor_name: "imu_sensor"
frame_id: "imu_link" frame_id: "imu_link"
unitree_guide_controller:
ros__parameters:
update_rate: 200 # Hz
joints:
- RF_HAA
- RF_HFE
- RF_KFE
- LF_HAA
- LF_HFE
- LF_KFE
- RH_HAA
- RH_HFE
- RH_KFE
- LH_HAA
- LH_HFE
- LH_KFE
down_pos:
- -0.0
- 1.41
- -2.58
- 0.0
- 1.41
- -2.58
- -0.0
- -1.41
- 2.58
- 0.0
- -1.41
- 2.58
stand_pos:
- 0.2
- 0.6
- -0.85
- -0.2
- 0.6
- -0.85
- 0.2
- -0.6
- 0.85
- -0.2
- -0.6
- 0.85
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- LF_FOOT
- RF_FOOT
- LH_FOOT
- RH_FOOT
imu_name: "imu_sensor"
base_name: "base"
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z
ocs2_quadruped_controller: ocs2_quadruped_controller:
ros__parameters: ros__parameters:
update_rate: 100 # Hz update_rate: 100 # Hz
@ -82,3 +160,90 @@ ocs2_quadruped_controller:
- RF - RF
- LH - LH
- RH - RH
rl_quadruped_controller:
ros__parameters:
update_rate: 200 # Hz
robot_pkg: "anymal_c_description"
model_folder: "legged_gym"
joints:
- LF_HAA
- LF_HFE
- LF_KFE
- RF_HAA
- RF_HFE
- RF_KFE
- LH_HAA
- LH_HFE
- LH_KFE
- RH_HAA
- RH_HFE
- RH_KFE
down_pos:
- -0.0
- 1.41
- -2.58
- 0.0
- 1.41
- -2.58
- -0.0
- -1.41
- 2.58
- 0.0
- -1.41
- 2.58
stand_pos:
- 0.2
- 0.6
- -0.85
- -0.2
- 0.6
- -0.85
- 0.2
- -0.6
- 0.85
- -0.2
- -0.6
- 0.85
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- LF_FOOT
- RF_FOOT
- LH_FOOT
- RH_FOOT
foot_force_name: "foot_force"
foot_force_interfaces:
- LF
- RF
- LH
- RH
imu_name: "imu_sensor"
base_name: "base"
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z

View File

@ -42,7 +42,7 @@ ros2 launch lite3_description visualize.launch.py
* RL Quadruped Controller * RL Quadruped Controller
```bash ```bash
source ~/ros2_ws/install/setup.bash source ~/ros2_ws/install/setup.bash
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=lite3_description model_folder:=legged_gym ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=lite3_description
``` ```
### Gazebo Classic 11 (ROS2 Humble) ### Gazebo Classic 11 (ROS2 Humble)

View File

@ -39,6 +39,12 @@ ros2 launch x30_description visualize.launch.py
source ~/ros2_ws/install/setup.bash source ~/ros2_ws/install/setup.bash
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=x30_description model_folder:=legged_gym ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=x30_description model_folder:=legged_gym
``` ```
* RL Quadruped Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=x30_description
```
### Gazebo Classic 11 (ROS2 Humble) ### Gazebo Classic 11 (ROS2 Humble)

View File

@ -15,18 +15,18 @@ clip_actions_upper: [100, 100, 100,
100, 100, 100, 100, 100, 100,
100, 100, 100, 100, 100, 100,
100, 100, 100] 100, 100, 100]
rl_kp: [160, 160, 160, rl_kp: [150.0, 150.0, 150.0,
160, 160, 160, 150.0, 150.0, 150.0,
160, 160, 160, 150.0, 150.0, 150.0,
160, 160, 160,] 150.0, 150.0, 150.0]
rl_kd: [8.0, 8.0, 8.0, rl_kd: [2.0, 2.0, 2.0,
8.0, 8.0, 8.0, 2.0, 2.0, 2.0,
8.0, 8.0, 8.0, 2.0, 2.0, 2.0,
8.0, 8.0, 8.0] 2.0, 2.0, 2.0]
hip_scale_reduction: 1.0 hip_scale_reduction: 1.0
hip_scale_reduction_indices: [0, 3, 6, 9] hip_scale_reduction_indices: [0, 3, 6, 9]
num_of_dofs: 12 num_of_dofs: 12
action_scale: 0.25 action_scale: 0.4
lin_vel_scale: 2.0 lin_vel_scale: 2.0
ang_vel_scale: 0.25 ang_vel_scale: 0.25

Binary file not shown.

View File

@ -165,6 +165,95 @@ ocs2_quadruped_controller:
- FR - FR
- HR - HR
rl_quadruped_controller:
ros__parameters:
update_rate: 200 # Hz
robot_pkg: "x30_description"
model_folder: "legged_gym"
stand_kp: 500.0
stand_kd: 20.0
joints:
- FL_HipX
- FL_HipY
- FL_Knee
- FR_HipX
- FR_HipY
- FR_Knee
- HL_HipX
- HL_HipY
- HL_Knee
- HR_HipX
- HR_HipY
- HR_Knee
down_pos:
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
stand_pos:
- 0.0
- -1.0
- 1.8
- 0.0
- -1.0
- 1.8
- 0.0
- -1.0
- 1.8
- 0.0
- -1.0
- 1.8
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- FL_FOOT
- FR_FOOT
- HL_FOOT
- HR_FOOT
foot_force_name: "foot_force"
foot_force_interfaces:
- FL
- FR
- HL
- HR
imu_name: "imu_sensor"
base_name: "base"
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z
rl_quadruped_controller: rl_quadruped_controller:
ros__parameters: ros__parameters:
update_rate: 200 # Hz update_rate: 200 # Hz

View File

@ -0,0 +1,41 @@
model_name: "policy.pt"
framework: "isaacgym"
rows: 4
cols: 3
decimation: 4
num_observations: 48
observations: ["lin_vel", "ang_vel", "gravity_vec", "commands", "dof_pos", "dof_vel", "actions"]
#observations_history: [6, 5, 4, 3, 2, 1, 0]
clip_obs: 100.0
clip_actions_lower: [-100, -100, -100,
-100, -100, -100,
-100, -100, -100,
-100, -100, -100]
clip_actions_upper: [100, 100, 100,
100, 100, 100,
100, 100, 100,
100, 100, 100]
rl_kp: [20, 20, 20,
20, 20, 20,
20, 20, 20,
20, 20, 20]
rl_kd: [0.75, 0.75, 0.75,
0.75, 0.75, 0.75,
0.75, 0.75, 0.75,
0.75, 0.75, 0.75]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: [0, 3, 6, 9]
num_of_dofs: 12
action_scale: 0.25
lin_vel_scale: 2.0
ang_vel_scale: 0.25
dof_pos_scale: 1.0
dof_vel_scale: 0.05
commands_scale: [2.0, 2.0, 0.25]
torque_limits: [33.5, 33.5, 33.5,
33.5, 33.5, 33.5,
33.5, 33.5, 33.5,
33.5, 33.5, 33.5]

View File

@ -16,6 +16,9 @@ controller_manager:
ocs2_quadruped_controller: ocs2_quadruped_controller:
type: ocs2_quadruped_controller/Ocs2QuadrupedController type: ocs2_quadruped_controller/Ocs2QuadrupedController
rl_quadruped_controller:
type: rl_quadruped_controller/LeggedGymController
imu_sensor_broadcaster: imu_sensor_broadcaster:
ros__parameters: ros__parameters:
sensor_name: "imu_sensor" sensor_name: "imu_sensor"
@ -132,3 +135,76 @@ ocs2_quadruped_controller:
- RL - RL
- FR - FR
- RR - RR
rl_quadruped_controller:
ros__parameters:
update_rate: 200 # Hz
robot_pkg: "aliengo_description"
model_folder: "legged_gym"
joints:
- FL_hip_joint
- FL_thigh_joint
- FL_calf_joint
- FR_hip_joint
- FR_thigh_joint
- FR_calf_joint
- RL_hip_joint
- RL_thigh_joint
- RL_calf_joint
- RR_hip_joint
- RR_thigh_joint
- RR_calf_joint
stand_pos:
- 0.1000
- 0.8000
- -1.5000
- -0.1000
- 0.8000
- -1.5000
- 0.1000
- 0.8000
- -1.5000
- -0.1000
- 0.8000
- -1.5000
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- FL_foot
- FR_foot
- RL_foot
- RR_foot
foot_force_name: "foot_force"
foot_force_interfaces:
- FL
- RL
- FR
- RR
imu_name: "imu_sensor"
base_name: "base"
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z

View File

@ -1,6 +1,6 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | --> <!-- | This document was autogenerated by xacro from xacro/robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<robot name="aliengo"> <robot name="aliengo">
@ -174,7 +174,6 @@
<state_interface name="RL"/> <state_interface name="RL"/>
</sensor> </sensor>
</ros2_control> </ros2_control>
<!-- <xacro:include filename="$(find aliengo_description)/xacro/gazebo.xacro"/>-->
<!-- Rotor related joint and link is only for demonstrate location. --> <!-- Rotor related joint and link is only for demonstrate location. -->
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. --> <!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
<link name="base"> <link name="base">
@ -196,7 +195,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/trunk.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/trunk.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
@ -254,7 +252,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.083 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 -0.083 0"/>
@ -301,7 +298,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -397,6 +393,30 @@
<inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/> <inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/>
</inertial> </inertial>
</link> </link>
<!-- FL leg -->
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="FR_hip_tran"> <transmission name="FR_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="FR_hip_joint"> <joint name="FR_hip_joint">
@ -446,7 +466,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.083 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 0.083 0"/>
@ -493,7 +512,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -589,6 +607,30 @@
<inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/> <inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/>
</inertial> </inertial>
</link> </link>
<!-- FL leg -->
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="FL_hip_tran"> <transmission name="FL_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="FL_hip_joint"> <joint name="FL_hip_joint">
@ -638,7 +680,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.083 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 -0.083 0"/>
@ -685,7 +726,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -781,6 +821,30 @@
<inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/> <inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/>
</inertial> </inertial>
</link> </link>
<!-- FL leg -->
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="RR_hip_tran"> <transmission name="RR_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="RR_hip_joint"> <joint name="RR_hip_joint">
@ -830,7 +894,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.083 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 0.083 0"/>
@ -877,7 +940,6 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="orange"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -973,6 +1035,30 @@
<inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/> <inertia ixx="1.6853999999999998e-05" ixy="0.0" ixz="0.0" iyy="1.6853999999999998e-05" iyz="0.0" izz="1.6853999999999998e-05"/>
</inertial> </inertial>
</link> </link>
<!-- FL leg -->
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="RL_hip_tran"> <transmission name="RL_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="RL_hip_joint"> <joint name="RL_hip_joint">

View File

@ -1,6 +1,6 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | --> <!-- | This document was autogenerated by xacro from xacro/robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<robot name="go1"> <robot name="go1">
@ -13,9 +13,15 @@
<material name="green"> <material name="green">
<color rgba="0.0 0.8 0.0 1.0"/> <color rgba="0.0 0.8 0.0 1.0"/>
</material> </material>
<material name="deep-grey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="grey"> <material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/> <color rgba="0.2 0.2 0.2 1.0"/>
</material> </material>
<material name="light-grey">
<color rgba="0.35 0.35 0.35 1.0"/>
</material>
<material name="silver"> <material name="silver">
<color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/> <color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/>
</material> </material>
@ -196,7 +202,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/trunk.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/trunk.dae" scale="1 1 1"/>
</geometry> </geometry>
<!-- <material name="orange"/> --> <material name="light-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
@ -254,7 +260,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<!-- <material name="orange"/> --> <material name="deep-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0"/>
@ -274,7 +280,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -301,6 +306,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh_mirror.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -320,7 +326,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -347,6 +352,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="light-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -396,6 +402,29 @@
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/> <inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial> </inertial>
</link> </link>
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="FR_hip_tran"> <transmission name="FR_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="FR_hip_joint"> <joint name="FR_hip_joint">
@ -445,7 +474,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<!-- <material name="orange"/> --> <material name="deep-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0"/>
@ -465,7 +494,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -492,6 +520,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -511,7 +540,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -538,6 +566,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="light-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -587,6 +616,29 @@
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/> <inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial> </inertial>
</link> </link>
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="FL_hip_tran"> <transmission name="FL_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="FL_hip_joint"> <joint name="FL_hip_joint">
@ -636,7 +688,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<!-- <material name="orange"/> --> <material name="deep-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0"/>
@ -656,7 +708,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -683,6 +734,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh_mirror.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -702,7 +754,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -729,6 +780,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="light-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -778,6 +830,29 @@
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/> <inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial> </inertial>
</link> </link>
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="RR_hip_tran"> <transmission name="RR_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="RR_hip_joint"> <joint name="RR_hip_joint">
@ -827,7 +902,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry> </geometry>
<!-- <material name="orange"/> --> <material name="deep-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0"/> <origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0"/>
@ -847,7 +922,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -874,6 +948,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -893,7 +968,6 @@
<geometry> <geometry>
<cylinder length="0.02" radius="0.035"/> <cylinder length="0.02" radius="0.035"/>
</geometry> </geometry>
<material name="green"/>
</visual> </visual>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
@ -920,6 +994,7 @@
<geometry> <geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/> <mesh filename="file:///home/tlab-uav/ros2_ws/install/go1_description/share/go1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry> </geometry>
<material name="light-grey"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/> <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
@ -969,6 +1044,29 @@
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/> <inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial> </inertial>
</link> </link>
<gazebo reference="{name}_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="{name}_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="{name}_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="{name}_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<transmission name="RL_hip_tran"> <transmission name="RL_hip_tran">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="RL_hip_joint"> <joint name="RL_hip_joint">
@ -1030,49 +1128,49 @@
</joint> </joint>
<link name="camera_optical_face"> <link name="camera_optical_face">
</link> </link>
<gazebo reference="camera_face"> <!-- <gazebo reference="camera_${name}">-->
<!-- <material>Gazebo/Black</material> --> <!-- &lt;!&ndash; <material>Gazebo/Black</material> &ndash;&gt;-->
<sensor name="camera_face_camera" type="depth"> <!-- <sensor name="camera_${name}_camera" type="depth">-->
<update_rate>16</update_rate> <!-- <update_rate>16</update_rate>-->
<camera> <!-- <camera>-->
<horizontal_fov>2.094</horizontal_fov> <!-- <horizontal_fov>2.094</horizontal_fov>-->
<image> <!-- <image>-->
<width>928</width> <!-- <width>928</width>-->
<height>800</height> <!-- <height>800</height>-->
<format>R8G8B8</format> <!-- <format>R8G8B8</format>-->
</image> <!-- </image>-->
<clip> <!-- <clip>-->
<near>0.1</near> <!-- <near>0.1</near>-->
<far>5</far> <!-- <far>5</far>-->
</clip> <!-- </clip>-->
</camera> <!-- </camera>-->
<plugin filename="libgazebo_ros_openni_kinect.so" name="camera_face_controller"> <!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
<baseline>0.025</baseline> <!-- <baseline>0.025</baseline>-->
<alwaysOn>true</alwaysOn> <!-- <alwaysOn>true</alwaysOn>-->
<updateRate>0.0</updateRate> <!-- <updateRate>0.0</updateRate>-->
<cameraName>camera_face_ir</cameraName> <!-- <cameraName>camera_${name}_ir</cameraName>-->
<imageTopicName>/camera_face/color/image_raw</imageTopicName> <!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
<cameraInfoTopicName>/camera_face/color/camera_info</cameraInfoTopicName> <!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
<depthImageTopicName>/camera_face/depth/image_raw</depthImageTopicName> <!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
<depthImageInfoTopicName>/camera_face/depth/camera_info</depthImageInfoTopicName> <!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
<!-- <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> --> <!-- &lt;!&ndash; <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> &ndash;&gt;-->
<pointCloudTopicName>/cam1/point_cloud_face</pointCloudTopicName> <!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
<frameName>camera_optical_face</frameName> <!-- <frameName>camera_optical_${name}</frameName>-->
<pointCloudCutoff>0.1</pointCloudCutoff> <!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
<pointCloudCutoffMax>1.5</pointCloudCutoffMax> <!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
<distortionK1>0.0</distortionK1> <!-- <distortionK1>0.0</distortionK1>-->
<distortionK2>0.0</distortionK2> <!-- <distortionK2>0.0</distortionK2>-->
<distortionK3>0.0</distortionK3> <!-- <distortionK3>0.0</distortionK3>-->
<distortionT1>0.0</distortionT1> <!-- <distortionT1>0.0</distortionT1>-->
<distortionT2>0.0</distortionT2> <!-- <distortionT2>0.0</distortionT2>-->
<CxPrime>0</CxPrime> <!-- <CxPrime>0</CxPrime>-->
<Cx>0.0045</Cx> <!-- <Cx>0.0045</Cx>-->
<Cy>0.0039</Cy> <!-- <Cy>0.0039</Cy>-->
<focalLength>0</focalLength> <!-- <focalLength>0</focalLength>-->
<hackBaseline>0</hackBaseline> <!-- <hackBaseline>0</hackBaseline>-->
</plugin> <!-- </plugin>-->
</sensor> <!-- </sensor>-->
</gazebo> <!-- </gazebo>-->
<joint name="camera_joint_chin" type="fixed"> <joint name="camera_joint_chin" type="fixed">
<origin rpy="3.141592653589793 1.5707963267948966 0" xyz="0.2522 0.0125 -0.0436"/> <origin rpy="3.141592653589793 1.5707963267948966 0" xyz="0.2522 0.0125 -0.0436"/>
<parent link="trunk"/> <parent link="trunk"/>
@ -1104,49 +1202,49 @@
</joint> </joint>
<link name="camera_optical_chin"> <link name="camera_optical_chin">
</link> </link>
<gazebo reference="camera_chin"> <!-- <gazebo reference="camera_${name}">-->
<!-- <material>Gazebo/Black</material> --> <!-- &lt;!&ndash; <material>Gazebo/Black</material> &ndash;&gt;-->
<sensor name="camera_chin_camera" type="depth"> <!-- <sensor name="camera_${name}_camera" type="depth">-->
<update_rate>16</update_rate> <!-- <update_rate>16</update_rate>-->
<camera> <!-- <camera>-->
<horizontal_fov>2.094</horizontal_fov> <!-- <horizontal_fov>2.094</horizontal_fov>-->
<image> <!-- <image>-->
<width>928</width> <!-- <width>928</width>-->
<height>800</height> <!-- <height>800</height>-->
<format>R8G8B8</format> <!-- <format>R8G8B8</format>-->
</image> <!-- </image>-->
<clip> <!-- <clip>-->
<near>0.1</near> <!-- <near>0.1</near>-->
<far>5</far> <!-- <far>5</far>-->
</clip> <!-- </clip>-->
</camera> <!-- </camera>-->
<plugin filename="libgazebo_ros_openni_kinect.so" name="camera_chin_controller"> <!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
<baseline>0.025</baseline> <!-- <baseline>0.025</baseline>-->
<alwaysOn>true</alwaysOn> <!-- <alwaysOn>true</alwaysOn>-->
<updateRate>0.0</updateRate> <!-- <updateRate>0.0</updateRate>-->
<cameraName>camera_chin_ir</cameraName> <!-- <cameraName>camera_${name}_ir</cameraName>-->
<imageTopicName>/camera_chin/color/image_raw</imageTopicName> <!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
<cameraInfoTopicName>/camera_chin/color/camera_info</cameraInfoTopicName> <!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
<depthImageTopicName>/camera_chin/depth/image_raw</depthImageTopicName> <!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
<depthImageInfoTopicName>/camera_chin/depth/camera_info</depthImageInfoTopicName> <!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
<!-- <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> --> <!-- &lt;!&ndash; <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> &ndash;&gt;-->
<pointCloudTopicName>/cam2/point_cloud_chin</pointCloudTopicName> <!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
<frameName>camera_optical_chin</frameName> <!-- <frameName>camera_optical_${name}</frameName>-->
<pointCloudCutoff>0.1</pointCloudCutoff> <!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
<pointCloudCutoffMax>1.5</pointCloudCutoffMax> <!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
<distortionK1>0.0</distortionK1> <!-- <distortionK1>0.0</distortionK1>-->
<distortionK2>0.0</distortionK2> <!-- <distortionK2>0.0</distortionK2>-->
<distortionK3>0.0</distortionK3> <!-- <distortionK3>0.0</distortionK3>-->
<distortionT1>0.0</distortionT1> <!-- <distortionT1>0.0</distortionT1>-->
<distortionT2>0.0</distortionT2> <!-- <distortionT2>0.0</distortionT2>-->
<CxPrime>0</CxPrime> <!-- <CxPrime>0</CxPrime>-->
<Cx>0.0045</Cx> <!-- <Cx>0.0045</Cx>-->
<Cy>0.0039</Cy> <!-- <Cy>0.0039</Cy>-->
<focalLength>0</focalLength> <!-- <focalLength>0</focalLength>-->
<hackBaseline>0</hackBaseline> <!-- <hackBaseline>0</hackBaseline>-->
</plugin> <!-- </plugin>-->
</sensor> <!-- </sensor>-->
</gazebo> <!-- </gazebo>-->
<joint name="camera_joint_left" type="fixed"> <joint name="camera_joint_left" type="fixed">
<origin rpy="3.141592653589793 0.2618 1.5707963267948966" xyz="-0.066 0.082 -0.0176"/> <origin rpy="3.141592653589793 0.2618 1.5707963267948966" xyz="-0.066 0.082 -0.0176"/>
<parent link="trunk"/> <parent link="trunk"/>
@ -1178,49 +1276,49 @@
</joint> </joint>
<link name="camera_optical_left"> <link name="camera_optical_left">
</link> </link>
<gazebo reference="camera_left"> <!-- <gazebo reference="camera_${name}">-->
<!-- <material>Gazebo/Black</material> --> <!-- &lt;!&ndash; <material>Gazebo/Black</material> &ndash;&gt;-->
<sensor name="camera_left_camera" type="depth"> <!-- <sensor name="camera_${name}_camera" type="depth">-->
<update_rate>16</update_rate> <!-- <update_rate>16</update_rate>-->
<camera> <!-- <camera>-->
<horizontal_fov>2.094</horizontal_fov> <!-- <horizontal_fov>2.094</horizontal_fov>-->
<image> <!-- <image>-->
<width>928</width> <!-- <width>928</width>-->
<height>800</height> <!-- <height>800</height>-->
<format>R8G8B8</format> <!-- <format>R8G8B8</format>-->
</image> <!-- </image>-->
<clip> <!-- <clip>-->
<near>0.1</near> <!-- <near>0.1</near>-->
<far>5</far> <!-- <far>5</far>-->
</clip> <!-- </clip>-->
</camera> <!-- </camera>-->
<plugin filename="libgazebo_ros_openni_kinect.so" name="camera_left_controller"> <!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
<baseline>0.025</baseline> <!-- <baseline>0.025</baseline>-->
<alwaysOn>true</alwaysOn> <!-- <alwaysOn>true</alwaysOn>-->
<updateRate>0.0</updateRate> <!-- <updateRate>0.0</updateRate>-->
<cameraName>camera_left_ir</cameraName> <!-- <cameraName>camera_${name}_ir</cameraName>-->
<imageTopicName>/camera_left/color/image_raw</imageTopicName> <!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
<cameraInfoTopicName>/camera_left/color/camera_info</cameraInfoTopicName> <!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
<depthImageTopicName>/camera_left/depth/image_raw</depthImageTopicName> <!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
<depthImageInfoTopicName>/camera_left/depth/camera_info</depthImageInfoTopicName> <!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
<!-- <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> --> <!-- &lt;!&ndash; <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> &ndash;&gt;-->
<pointCloudTopicName>/cam3/point_cloud_left</pointCloudTopicName> <!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
<frameName>camera_optical_left</frameName> <!-- <frameName>camera_optical_${name}</frameName>-->
<pointCloudCutoff>0.1</pointCloudCutoff> <!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
<pointCloudCutoffMax>1.5</pointCloudCutoffMax> <!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
<distortionK1>0.0</distortionK1> <!-- <distortionK1>0.0</distortionK1>-->
<distortionK2>0.0</distortionK2> <!-- <distortionK2>0.0</distortionK2>-->
<distortionK3>0.0</distortionK3> <!-- <distortionK3>0.0</distortionK3>-->
<distortionT1>0.0</distortionT1> <!-- <distortionT1>0.0</distortionT1>-->
<distortionT2>0.0</distortionT2> <!-- <distortionT2>0.0</distortionT2>-->
<CxPrime>0</CxPrime> <!-- <CxPrime>0</CxPrime>-->
<Cx>0.0045</Cx> <!-- <Cx>0.0045</Cx>-->
<Cy>0.0039</Cy> <!-- <Cy>0.0039</Cy>-->
<focalLength>0</focalLength> <!-- <focalLength>0</focalLength>-->
<hackBaseline>0</hackBaseline> <!-- <hackBaseline>0</hackBaseline>-->
</plugin> <!-- </plugin>-->
</sensor> <!-- </sensor>-->
</gazebo> <!-- </gazebo>-->
<joint name="camera_joint_right" type="fixed"> <joint name="camera_joint_right" type="fixed">
<origin rpy="3.141592653589793 0.2618 -1.5707963267948966" xyz="-0.041 -0.082 -0.0176"/> <origin rpy="3.141592653589793 0.2618 -1.5707963267948966" xyz="-0.041 -0.082 -0.0176"/>
<parent link="trunk"/> <parent link="trunk"/>
@ -1252,49 +1350,49 @@
</joint> </joint>
<link name="camera_optical_right"> <link name="camera_optical_right">
</link> </link>
<gazebo reference="camera_right"> <!-- <gazebo reference="camera_${name}">-->
<!-- <material>Gazebo/Black</material> --> <!-- &lt;!&ndash; <material>Gazebo/Black</material> &ndash;&gt;-->
<sensor name="camera_right_camera" type="depth"> <!-- <sensor name="camera_${name}_camera" type="depth">-->
<update_rate>16</update_rate> <!-- <update_rate>16</update_rate>-->
<camera> <!-- <camera>-->
<horizontal_fov>2.094</horizontal_fov> <!-- <horizontal_fov>2.094</horizontal_fov>-->
<image> <!-- <image>-->
<width>928</width> <!-- <width>928</width>-->
<height>800</height> <!-- <height>800</height>-->
<format>R8G8B8</format> <!-- <format>R8G8B8</format>-->
</image> <!-- </image>-->
<clip> <!-- <clip>-->
<near>0.1</near> <!-- <near>0.1</near>-->
<far>5</far> <!-- <far>5</far>-->
</clip> <!-- </clip>-->
</camera> <!-- </camera>-->
<plugin filename="libgazebo_ros_openni_kinect.so" name="camera_right_controller"> <!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
<baseline>0.025</baseline> <!-- <baseline>0.025</baseline>-->
<alwaysOn>true</alwaysOn> <!-- <alwaysOn>true</alwaysOn>-->
<updateRate>0.0</updateRate> <!-- <updateRate>0.0</updateRate>-->
<cameraName>camera_right_ir</cameraName> <!-- <cameraName>camera_${name}_ir</cameraName>-->
<imageTopicName>/camera_right/color/image_raw</imageTopicName> <!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
<cameraInfoTopicName>/camera_right/color/camera_info</cameraInfoTopicName> <!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
<depthImageTopicName>/camera_right/depth/image_raw</depthImageTopicName> <!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
<depthImageInfoTopicName>/camera_right/depth/camera_info</depthImageInfoTopicName> <!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
<!-- <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> --> <!-- &lt;!&ndash; <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> &ndash;&gt;-->
<pointCloudTopicName>/cam4/point_cloud_right</pointCloudTopicName> <!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
<frameName>camera_optical_right</frameName> <!-- <frameName>camera_optical_${name}</frameName>-->
<pointCloudCutoff>0.1</pointCloudCutoff> <!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
<pointCloudCutoffMax>1.5</pointCloudCutoffMax> <!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
<distortionK1>0.0</distortionK1> <!-- <distortionK1>0.0</distortionK1>-->
<distortionK2>0.0</distortionK2> <!-- <distortionK2>0.0</distortionK2>-->
<distortionK3>0.0</distortionK3> <!-- <distortionK3>0.0</distortionK3>-->
<distortionT1>0.0</distortionT1> <!-- <distortionT1>0.0</distortionT1>-->
<distortionT2>0.0</distortionT2> <!-- <distortionT2>0.0</distortionT2>-->
<CxPrime>0</CxPrime> <!-- <CxPrime>0</CxPrime>-->
<Cx>0.0045</Cx> <!-- <Cx>0.0045</Cx>-->
<Cy>0.0039</Cy> <!-- <Cy>0.0039</Cy>-->
<focalLength>0</focalLength> <!-- <focalLength>0</focalLength>-->
<hackBaseline>0</hackBaseline> <!-- <hackBaseline>0</hackBaseline>-->
</plugin> <!-- </plugin>-->
</sensor> <!-- </sensor>-->
</gazebo> <!-- </gazebo>-->
<joint name="camera_joint_rearDown" type="fixed"> <joint name="camera_joint_rearDown" type="fixed">
<origin rpy="3.141592653589793 1.5707963267948966 0" xyz="-0.0825 0.0125 -0.04365"/> <origin rpy="3.141592653589793 1.5707963267948966 0" xyz="-0.0825 0.0125 -0.04365"/>
<parent link="trunk"/> <parent link="trunk"/>
@ -1326,49 +1424,49 @@
</joint> </joint>
<link name="camera_optical_rearDown"> <link name="camera_optical_rearDown">
</link> </link>
<gazebo reference="camera_rearDown"> <!-- <gazebo reference="camera_${name}">-->
<!-- <material>Gazebo/Black</material> --> <!-- &lt;!&ndash; <material>Gazebo/Black</material> &ndash;&gt;-->
<sensor name="camera_rearDown_camera" type="depth"> <!-- <sensor name="camera_${name}_camera" type="depth">-->
<update_rate>16</update_rate> <!-- <update_rate>16</update_rate>-->
<camera> <!-- <camera>-->
<horizontal_fov>2.094</horizontal_fov> <!-- <horizontal_fov>2.094</horizontal_fov>-->
<image> <!-- <image>-->
<width>928</width> <!-- <width>928</width>-->
<height>800</height> <!-- <height>800</height>-->
<format>R8G8B8</format> <!-- <format>R8G8B8</format>-->
</image> <!-- </image>-->
<clip> <!-- <clip>-->
<near>0.1</near> <!-- <near>0.1</near>-->
<far>5</far> <!-- <far>5</far>-->
</clip> <!-- </clip>-->
</camera> <!-- </camera>-->
<plugin filename="libgazebo_ros_openni_kinect.so" name="camera_rearDown_controller"> <!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
<baseline>0.025</baseline> <!-- <baseline>0.025</baseline>-->
<alwaysOn>true</alwaysOn> <!-- <alwaysOn>true</alwaysOn>-->
<updateRate>0.0</updateRate> <!-- <updateRate>0.0</updateRate>-->
<cameraName>camera_rearDown_ir</cameraName> <!-- <cameraName>camera_${name}_ir</cameraName>-->
<imageTopicName>/camera_rearDown/color/image_raw</imageTopicName> <!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
<cameraInfoTopicName>/camera_rearDown/color/camera_info</cameraInfoTopicName> <!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
<depthImageTopicName>/camera_rearDown/depth/image_raw</depthImageTopicName> <!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
<depthImageInfoTopicName>/camera_rearDown/depth/camera_info</depthImageInfoTopicName> <!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
<!-- <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> --> <!-- &lt;!&ndash; <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> &ndash;&gt;-->
<pointCloudTopicName>/cam5/point_cloud_rearDown</pointCloudTopicName> <!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
<frameName>camera_optical_rearDown</frameName> <!-- <frameName>camera_optical_${name}</frameName>-->
<pointCloudCutoff>0.1</pointCloudCutoff> <!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
<pointCloudCutoffMax>1.5</pointCloudCutoffMax> <!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
<distortionK1>0.0</distortionK1> <!-- <distortionK1>0.0</distortionK1>-->
<distortionK2>0.0</distortionK2> <!-- <distortionK2>0.0</distortionK2>-->
<distortionK3>0.0</distortionK3> <!-- <distortionK3>0.0</distortionK3>-->
<distortionT1>0.0</distortionT1> <!-- <distortionT1>0.0</distortionT1>-->
<distortionT2>0.0</distortionT2> <!-- <distortionT2>0.0</distortionT2>-->
<CxPrime>0</CxPrime> <!-- <CxPrime>0</CxPrime>-->
<Cx>0.0045</Cx> <!-- <Cx>0.0045</Cx>-->
<Cy>0.0039</Cy> <!-- <Cy>0.0039</Cy>-->
<focalLength>0</focalLength> <!-- <focalLength>0</focalLength>-->
<hackBaseline>0</hackBaseline> <!-- <hackBaseline>0</hackBaseline>-->
</plugin> <!-- </plugin>-->
</sensor> <!-- </sensor>-->
</gazebo> <!-- </gazebo>-->
<joint name="camera_laserscan_joint_left" type="fixed"> <joint name="camera_laserscan_joint_left" type="fixed">
<origin rpy="0 0.2618 0" xyz="0 0 0"/> <origin rpy="0 0.2618 0" xyz="0 0 0"/>
<parent link="camera_left"/> <parent link="camera_left"/>

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 200 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster: