Skip to content
Snippets Groups Projects
Commit b01c5cb7 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Added a namespace in the CNY70 sensors.

Added a control parameter file for the Darwin robot used for the CEABOT competition.
parent 84bbaa6d
No related branches found
No related tags found
1 merge request!8Kinetic migration
darwin:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
darwin_controller:
type: effort_controllers/DarwinController
joints:
- j_shoulder_pitch_r
- j_shoulder_pitch_l
- j_shoulder_roll_r
- j_shoulder_roll_l
- j_elbow_r
- j_elbow_l
- j_hip_yaw_r
- j_hip_yaw_l
- j_hip_roll_r
- j_hip_roll_l
- j_hip_pitch_r
- j_hip_pitch_l
- j_knee_r
- j_knee_l
- j_ankle_pitch_r
- j_ankle_pitch_l
- j_ankle_roll_r
- j_ankle_roll_l
- j_pan
- j_tilt
gains:
j_shoulder_pitch_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_shoulder_roll_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_elbow_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_shoulder_pitch_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_shoulder_roll_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_elbow_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_hip_yaw_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_hip_roll_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_hip_pitch_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_knee_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_ankle_pitch_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_ankle_roll_l:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_hip_yaw_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_hip_roll_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_hip_pitch_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_knee_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_ankle_pitch_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_ankle_roll_r:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_pan:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
j_tilt:
p: 16.0
d: 0.0
i: 0.0
i_clamp: 100
......@@ -49,35 +49,35 @@
</actuator>
</transmission>
<xacro:cny70_ir name="left_down_right_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_right_rear" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.0185 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_down_right_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_right_middle" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.0185 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_down_right_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_right_front" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.011 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_down_left_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_left_rear" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.0335 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_down_left_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_left_middle" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.0335 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_down_left_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_left_front" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.026 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_front_right" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_front_right" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.0186 -0.0285 0.051" rpy="0 -1.5707 0" />
</xacro:cny70_ir>
<xacro:cny70_ir name="left_front_left" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_front_left" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.0336 -0.0285 0.051" rpy="-1.5707 -1.5707 0" />
</xacro:cny70_ir>
......
......@@ -49,35 +49,35 @@
</actuator>
</transmission>
<xacro:cny70_ir name="right_down_right_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_right_rear" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.0335 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_down_right_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_right_middle" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.0335 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_down_right_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_right_front" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.026 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_down_left_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_left_rear" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.0185 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_down_left_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_left_middle" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.0185 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_down_left_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_left_front" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.011 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_front_right" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_front_right" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="-0.0336 -0.0285 0.051" rpy="0 -1.5707 0" />
</xacro:cny70_ir>
<xacro:cny70_ir name="right_front_left" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_front_left" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<origin xyz="0.0186 -0.0285 0.051" rpy="-1.5707 -1.5707 0" />
</xacro:cny70_ir>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment