Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add waist_imu in urdf file #99

Merged
merged 7 commits into from
May 5, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions urdf/ergoCub/conf/estimators/wbd_ecub_sim.xml
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
<elem name="left_lower_arm">left_arm-mc_wrapper</elem-->
<!-- imu -->
<elem name="imu">head_inertial_hardware_device</elem>
<elem name="waist_imu">waist_inertial_hardware_device</elem>
<!-- ft -->
<elem name="l_arm_ft_sensor">ergocub_left_arm_ft</elem>
<elem name="r_arm_ft_sensor">ergocub_right_arm_ft</elem>
Expand Down
8 changes: 6 additions & 2 deletions urdf/ergoCub/conf/launch_wholebodydynamics_ecub.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,12 @@
<param name="remote"> /ergocubSim/head/inertials </param>
<param name="local"> /wholeBodyDynamics/imu </param>
</device>



<device name="waist_inertial_hardware_device" type="multipleanalogsensorsclient">
<param name="remote"> /ergocubSim/waist/inertials </param>
<param name="local"> /wholeBodyDynamics/waist_imu </param>
</device>

<!-- six axis force torque sensors -->
<device name="ergocub_left_arm_ft" type="multipleanalogsensorsclient">
<param name="remote"> /ergocubSim/left_arm </param>
Expand Down
45 changes: 43 additions & 2 deletions urdf/simmechanics/data/ergocub/ERGOCUB_all_options.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -808,8 +808,7 @@ sensors:
- |
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_inertial.ini</yarpConfigurationFile>
</plugin>

</plugin>
- sensorName: default
exportFrameInURDF: No
sensorType: "depth"
Expand Down Expand Up @@ -937,6 +936,16 @@ sensors:
<yarpConfigurationFile>model://ergoCub/conf/sensors/gazebo_ergocub_lidar.ini</yarpConfigurationFile>
</plugin>

assignedMasses:
torso_1 : 2.0645667

assignedInertias:
# This is due to https://github.com/robotology/icub-models/issues/33
- linkName: torso_1
xx: 0.0074060860
yy: 0.0059470733
zz: 0.0031780111

assignedColors:
root_link : [0.70, 0.70, 0.70, 1]
torso_1 : [0.70, 0.70, 0.70, 1]
Expand Down Expand Up @@ -1018,6 +1027,38 @@ reverseRotationAxis:
# neck_yaw

XMLBlobs:
# imu waist (workaround since simmechanics was not updated)
- |
<link name="waist_imu_0"/>
- |
<joint name="waist_imu_0_fixed_joint" type="fixed">
<origin xyz="0.0354497 0.00639688 0.060600" rpy="-1.5707322 1.5707963 0"/>
<parent link="torso_1"/>
<child link="waist_imu_0"/>
<dynamics damping="0.1"/>
</joint>
- |
<gazebo>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_waist_inertial.ini</yarpConfigurationFile>
</plugin>
</gazebo>
- |
<gazebo reference="torso_1">
<sensor name="waist_imu_0" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.0354497 0.00639688 0.060600 -1.5707322 1.5707963 0</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_waist_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="waist_imu_0" type="accelerometer">
<parent link="torso_1"/>
<origin rpy="-1.5707322 1.5707963 0" xyz="0.0354497 0.00639688 0.060600"/>
</sensor>
# upperbody
- |
<link name="base_link" />
Expand Down
38 changes: 38 additions & 0 deletions urdf/simmechanics/data/ergocub/ERGOCUB_all_options_gazebo.yaml.in
Original file line number Diff line number Diff line change
Expand Up @@ -936,9 +936,15 @@ sensors:


@ASSIGNED_COLLISION_GEOMETRIES@
assignedMasses:
torso_1 : 2.0645667

assignedInertias:
# This is due to https://github.com/robotology/icub-models/issues/33
- linkName: torso_1
xx: 0.0074060860
yy: 0.0059470733
zz: 0.0031780111
- linkName: realsense
xx: 0.01
yy: 0.01
Expand Down Expand Up @@ -1216,6 +1222,38 @@ reverseRotationAxis:
# neck_yaw

XMLBlobs:
# imu waist (workaround since simmechanics was not updated)
- |
<link name="waist_imu_0"/>
- |
<joint name="waist_imu_0_fixed_joint" type="fixed">
<origin xyz="0.0354497 0.00639688 0.060600" rpy="-1.5707322 1.5707963 0"/>
<parent link="torso_1"/>
<child link="waist_imu_0"/>
<dynamics damping="0.1"/>
</joint>
- |
<gazebo>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_waist_inertial.ini</yarpConfigurationFile>
</plugin>
</gazebo>
- |
<gazebo reference="torso_1">
<sensor name="waist_imu_0" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.0354497 0.00639688 0.060600 -1.5707322 1.5707963 0</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_waist_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="waist_imu_0" type="accelerometer">
<parent link="torso_1"/>
<origin rpy="-1.5707322 1.5707963 0" xyz="0.0354497 0.00639688 0.060600"/>
</sensor>
# upperbody
- |
<link name="base_link" />
Expand Down
1 change: 1 addition & 0 deletions urdf/simmechanics/data/ergocub/conf/ergocub.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@

<!-- INERTIAL SENSOR-->
<xi:include href="wrappers/inertials/head-inertials_wrapper.xml" />
<xi:include href="wrappers/inertials/waist-inertials_wrapper.xml" />

<!-- HEAD SENSORS -->
<xi:include href="sensors/rgbd_camera_wrapper.xml" />
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName waist_inertial_hardware_device
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">


<device xmlns:xi="http://www.w3.org/2001/XInclude" name="waist-inertials_wrapper" type="multipleanalogsensorsserver">
<param name="period"> 10 </param>
<param name="name"> ${portprefix}/waist/inertials </param>


<action phase="startup" level="10" type="attach">
<paramlist name="networks">
<elem name="SetOfIMUs"> waist_inertial_hardware_device </elem>
</paramlist>
</action>

<action phase="shutdown" level="15" type="detach" />
</device>