Skip to content
Snippets Groups Projects
Commit 09a9b25e authored by Laia Freixas Mateu's avatar Laia Freixas Mateu
Browse files

added dexter.xacro and dexter.yaml files

parent 674e252a
No related branches found
No related tags found
No related merge requests found
bioloid:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
bioloid_cm510_cont:
type: effort_controllers/BioloidControllerCM510
adc1_frame: IR1_link
adc3_frame: gyro_x
adc4_frame: gyro_y
exp_board_id: 192
exp_gpio0_frame: left_front_fwd_ir_link
exp_gpio1_frame: left_front_dwn_ir_link
exp_gpio2_frame: left_lateral_dwn_ir_link
exp_gpio3_frame: right_front_fwd_ir_link
exp_gpio4_frame: right_front_dwn_ir_link
exp_gpio5_frame: right_lateral_dwn_ir_link
joints:
- j_shoulder_r
- j_shoulder_l
- j_high_arm_r
- j_high_arm_l
- j_low_arm_r
- j_low_arm_l
- j_pelvis_yaw_r
- j_pelvis_yaw_l
- j_pelvis_roll_r
- j_pelvis_roll_l
- j_pelvis_pitch_r
- j_pelvis_pitch_l
- j_knee_r
- j_knee_l
- j_ankle_pitch_r
- j_ankle_pitch_l
- j_ankle_roll_r
- j_ankle_roll_l
gains:
j_shoulder_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_high_arm_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_low_arm_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_shoulder_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_high_arm_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_low_arm_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_pelvis_yaw_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_pelvis_roll_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_pelvis_pitch_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_knee_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_ankle_pitch_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_ankle_roll_l:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_pelvis_yaw_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_pelvis_roll_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_pelvis_pitch_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_knee_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_ankle_pitch_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
j_ankle_roll_r:
p: 8.0
d: 0.0
i: 0.0
proxy:
lambda: 3.0
vel_limit: 6.0
effort_limit: 1.5
<robot name="bioloid" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find bioloid_description)/urdf/bioloid.xacro" />
<xacro:include filename="$(find bioloid_description)/urdf/bioloid_ceabot.gazebo" />
<xacro:include filename="$(find bioloid_description)/urdf/sensors/sharp_ir.xacro" />
<xacro:include filename="$(find bioloid_description)/urdf/sensors/feet_ir.xacro" />
<xacro:sharp_ir name="IR1" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8">
<origin xyz="0 0.0 0.035" rpy="-1.5707 -1.5707 0" />
</xacro:sharp_ir>
<xacro:sharp_ir name="IR2" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8">
<origin xyz="0 -0.05 0.035" rpy="-1.5707 -1.5707 0" />
</xacro:sharp_ir>
<xacro:sharp_ir name="IR3" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8">
<origin xyz="0 0.05 0.035" rpy="-1.5707 -1.5707 0" />
</xacro:sharp_ir>
<!-- <xacro:feet_ir left_parent="left_leg_ankle_roll" right_parent="right_leg_ankle_roll" update_rate="20" range="0.01"/>-->
<link name="battery_pack">
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://bioloid_description/meshes/bounding_boxes/battery_bb.stl" />
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://bioloid_description/meshes/bounding_boxes/battery_bb.stl" />
</geometry>
<material name="Grey">
<color rgba="0.79 0.82 0.93 1.0"/>
</material>
</visual>
<inertial>
<mass value="0.083" />
<origin xyz="-0.00750000 0.00000000 0.00000000" rpy="0 0 0"/>
<inertia ixx="0.00004236" ixy="0.00000000" ixz="0.00000000" iyy="0.00001003" iyz="0.00000000" izz="0.00003545" />
</inertial>
</link>
<joint name="j_battery" type="fixed">
<parent link="base_link"/>
<child link="battery_pack"/>
<origin xyz="0 -0.06 -0.022" rpy="-1.5707 -1.5707 0" />
</joint>
<link name="controller">
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://bioloid_description/meshes/bounding_boxes/cm510_bb.stl" />
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://bioloid_description/meshes/bounding_boxes/cm510_bb.stl" />
</geometry>
<material name="Grey">
<color rgba="0.79 0.82 0.93 1.0"/>
</material>
</visual>
<inertial>
<mass value="0.0513" />
<origin xyz="-0.01301673 -0.00039419 0.00111614" rpy="0 0 0"/>
<inertia ixx="0.00004774" ixy="0.00000038" ixz="-0.00000094" iyy="0.00002476" iyz="-0.00000030" izz="0.00004497" />
</inertial>
</link>
<joint name="j_controller" type="fixed">
<parent link="base_link"/>
<child link="controller"/>
<origin xyz="0 -0.01 -0.022" rpy="-1.5707 -1.5707 0" />
</joint>
</robot>
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