Small tweaking of the PIDs..Added Xtion helmet.
This commit is contained in:
parent
ff9305831a
commit
cd5c50599c
@ -1,52 +1,52 @@
|
||||
nao_dcm/gazebo_ros_control/pid_gains:
|
||||
HeadYaw: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
HeadYaw: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
HeadPitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
HeadPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LShoulderPitch: {p: 5000.0, i: 0.0, d: 0.0}
|
||||
LShoulderPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LElbowYaw: {p: 100.0, i: 0.0, d: 0.0}
|
||||
LElbowYaw: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LElbowRoll: {p: 100.0, i: 0.0, d: 0.0}
|
||||
LElbowRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LShoulderRoll: {p: 5000.0, i: 0.0, d: 0.0}
|
||||
LShoulderRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LWristYaw: {p: 20.0, i: 0.0, d: 0.0}
|
||||
LWristYaw: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LHand: {p: 1.0, i: 0.0, d: 0.0}
|
||||
LHand: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RShoulderPitch: {p: 5000.0, i: 0.0, d: 0.0}
|
||||
RShoulderPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RElbowYaw: {p: 100.0, i: 0.0, d: 0.0}
|
||||
RElbowYaw: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RElbowRoll: {p: 100.0, i: 0.0, d: 0.0}
|
||||
RElbowRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RShoulderRoll: {p: 5000.0, i: 0.0, d: 0.0}
|
||||
RShoulderRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RWristYaw: {p: 20.0, i: 0.0, d: 0.0}
|
||||
RWristYaw: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RHand: {p: 1.0, i: 0.0, d: 0.0}
|
||||
RHand: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LHipYawPitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
LHipYawPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LHipRoll: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
LHipRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LHipPitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
LHipPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LKneePitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
LKneePitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LAnklePitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
LAnklePitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
LAnkleRoll: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
LAnkleRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RHipYawPitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
RHipYawPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RHipRoll: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
RHipRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RHipPitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
RHipPitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RKneePitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
RKneePitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RAnklePitch: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
RAnklePitch: {p: 500.0, i: 1000.0, d: 0.01}
|
||||
|
||||
RAnkleRoll: {p: 1000.0, i: 0.0, d: 0.0}
|
||||
RAnkleRoll: {p: 500.0, i: 1000.0, d: 0.01}
|
61
nao_dcm_common/nao_dcm_description/meshes/helmet_xtion.dae
Normal file
61
nao_dcm_common/nao_dcm_description/meshes/helmet_xtion.dae
Normal file
File diff suppressed because one or more lines are too long
BIN
nao_dcm_common/nao_dcm_description/meshes/helmet_xtion.stl
Normal file
BIN
nao_dcm_common/nao_dcm_description/meshes/helmet_xtion.stl
Normal file
Binary file not shown.
@ -0,0 +1,28 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- XACRO MACROS FOR VISUALS AND COLLISIONS -->
|
||||
<xacro:macro name="visuals_collisions_helmet_xtion" params="">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_dcm_description/meshes/helmet_xtion.dae"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_dcm_description/meshes/helmet_xtion.dae"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
</xacro:macro>
|
||||
<joint name="head-helmet-xtion" type="fixed">
|
||||
<parent link="gaze"/>
|
||||
<child link="helmet-xtion"/>
|
||||
<origin xyz="0 0 0.095" rpy="0 0 0"/>
|
||||
</joint>
|
||||
<link name="helmet-xtion">
|
||||
<xacro:visuals_collisions_helmet_xtion/>
|
||||
</link>
|
||||
</robot>
|
@ -6,8 +6,9 @@
|
||||
<xacro:property name="PI_2" value="1.57079632679" />
|
||||
<xacro:property name="scale" value="0.001" />
|
||||
<xacro:property name="nao_meshes" value="true" />
|
||||
<xacro:property name="use_helmet" value="true" />
|
||||
<xacro:property name="use_helmet" value="false" />
|
||||
<xacro:property name="helmet_cameras_viz" value="false" />
|
||||
<xacro:property name="use_xtion" value="true" />
|
||||
<xacro:property name="use_odroid" value="true" />
|
||||
<xacro:property name="use_hector_imu" value="false" />
|
||||
<xacro:property name="effort_type1" value="0.0161" />
|
||||
@ -47,6 +48,11 @@
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/helmet_cameras.xacro" />
|
||||
</xacro:if>
|
||||
|
||||
<!-- Whether to use Nao helmet with ASUS Xtion or not -->
|
||||
<xacro:if value="${use_xtion}">
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/helmet_xtion.xacro" />
|
||||
</xacro:if>
|
||||
|
||||
<!-- Whether to use Odroid or not -->
|
||||
<xacro:if value="${use_odroid}">
|
||||
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/odroid_bag.xacro" />
|
||||
|
@ -93,7 +93,6 @@
|
||||
<mimicJoint>RHipYawPitch</mimicJoint>
|
||||
<multiplier>1.0</multiplier>
|
||||
<offset>0.0</offset>
|
||||
<sensitiveness>0.1</sensitiveness>
|
||||
</plugin>
|
||||
|
||||
<xacro:FingerMimics side="L" num="1"/>
|
||||
|
Loading…
Reference in New Issue
Block a user