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

Added the battery pack and the cm510 controller STL models.

Added a new motions file with all the standard motion actions.
parent 8df888d7
No related branches found
No related tags found
No related merge requests found
Pipeline #
......@@ -127,6 +127,7 @@ add_library(${PROJECT_NAME} src/bioloid_controller_cm510.cpp
${BIOLOID_FW_PATH}/communications/src/serial_console.c
# main application module
${ProjectPath}/movements/movements.c
${ProjectPath}/movements/mtn_library.c
# AVR simulation modules
src/sim/avr_delay.c
src/sim/avr_registers.c
......
......@@ -528,7 +528,7 @@ namespace bioloid_controller_cm510
try{
memset(&pages[0],0x00,sizeof(TActionPage));
for(page_id=1;page_id<MAX_PAGES;page_id++)
for(page_id=1;page_id<motions.get_num_pages();page_id++)
{
CRobotisPage robotis_page=motions.get_page(page_id-1);
......
source diff could not be displayed: it is too large. Options to address this: view the blob.
File added
File added
......@@ -15,4 +15,62 @@
</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