Skip to content

Commit

Permalink
First commit
Browse files Browse the repository at this point in the history
  • Loading branch information
xela-95 committed Mar 5, 2024
0 parents commit 5c51248
Show file tree
Hide file tree
Showing 379 changed files with 28,982 additions and 0 deletions.
3 changes: 3 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"xml.downloadExternalResources.enabled": true
}
74 changes: 74 additions & 0 deletions example.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<?xml version="1.0"?>

<sdf version="1.7">
<world name="turorial_controlboard">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<include>
<pose>0 0 0.5 0 -0.1 3.14</pose>
<!-- <uri>model://ergoCubSN001_fixed</uri> -->
<uri>model://ergoCub/robots/ergoCubGazeboV1_1_fixed</uri>
</include>

</world>
</sdf>
Binary file added install/lib/yarp/yarp_couplingXCubHandMk5.so
Binary file not shown.
Empty file.
2 changes: 2 additions & 0 deletions install/share/ergoCub/conf/FT/gazebo_ergocub_left_arm_ft.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_left_arm_ft
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_left_foot_front_ft
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_left_foot_rear_ft
2 changes: 2 additions & 0 deletions install/share/ergoCub/conf/FT/gazebo_ergocub_left_leg_ft.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_left_leg_ft
2 changes: 2 additions & 0 deletions install/share/ergoCub/conf/FT/gazebo_ergocub_right_arm_ft.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_right_arm_ft
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_right_foot_front_ft
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_right_foot_rear_ft
3 changes: 3 additions & 0 deletions install/share/ergoCub/conf/FT/gazebo_ergocub_right_leg_ft.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
disableImplicitNetworkWrapper
yarpDeviceName ergocub_right_leg_ft

43 changes: 43 additions & 0 deletions install/share/ergoCub/conf/ergocub.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE robot PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">

<robot name="ergocubGazebo" build="1" portprefix="/ergocubSim" xmlns:xi="http://www.w3.org/2001/XInclude">

<devices>

<!-- MOTOR CONTROLLERS -->
<xi:include href="wrappers/motorControl/left_arm-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/right_arm-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/left_leg-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/right_leg-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/head-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/torso-mc_wrapper.xml" />

<xi:include href="wrappers/motorControl/left_arm-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/right_arm-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/left_leg-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/right_leg-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/head-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/torso-mc_remapper.xml" />
<!-- ANALOG SENSORS FT -->
<xi:include href="wrappers/FT/left_leg-FT_remapper.xml" />
<xi:include href="wrappers/FT/right_leg-FT_remapper.xml" />
<xi:include href="wrappers/FT/left_leg-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_leg-FT_wrapper.xml" />
<xi:include href="wrappers/FT/left_arm-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_arm-FT_wrapper.xml" />

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

<!-- HEAD SENSORS -->
<xi:include href="sensors/rgbd_camera_wrapper.xml" />
<xi:include href="sensors/lidar_wrapper.xml" />

</devices>
</robot>
43 changes: 43 additions & 0 deletions install/share/ergoCub/conf/ergocub_ros2.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE robot PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">

<robot name="ergocubGazebo" build="1" portprefix="/ergocubSim" xmlns:xi="http://www.w3.org/2001/XInclude">

<devices>

<!-- MOTOR CONTROLLERS -->
<xi:include href="wrappers/motorControl/left_arm-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/right_arm-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/left_leg-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/right_leg-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/head-mc_wrapper.xml" />
<xi:include href="wrappers/motorControl/torso-mc_wrapper.xml" />

<xi:include href="wrappers/motorControl/left_arm-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/right_arm-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/left_leg-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/right_leg-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/head-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/torso-mc_remapper.xml" />

<xi:include href="wrappers/motorControl/all-mc_remapper.xml" />
<xi:include href="wrappers/motorControl/all-mc_remapper_ros2.xml" />
<!-- ANALOG SENSORS FT -->
<xi:include href="wrappers/FT/left_leg-FT_remapper.xml" />
<xi:include href="wrappers/FT/right_leg-FT_remapper.xml" />
<xi:include href="wrappers/FT/left_leg-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_leg-FT_wrapper.xml" />
<xi:include href="wrappers/FT/left_arm-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_arm-FT_wrapper.xml" />

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

<!-- HEAD SENSORS -->
<xi:include href="sensors/rgbd_camera_wrapper.xml" />
<xi:include href="sensors/rgbd_camera_wrapper_ros2.xml" />
<xi:include href="sensors/lidar_wrapper.xml" />
<xi:include href="sensors/lidar_wrapper_ros2.xml" />

</devices>
</robot>
74 changes: 74 additions & 0 deletions install/share/ergoCub/conf/estimators/wbd_ecub_sim.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">

<devices robot="ergoCubGazeboV1" build="1">
<device name="wholebodydynamics" type="wholebodydynamics">
<param name="axesNames">(torso_roll,torso_pitch,torso_yaw,l_shoulder_pitch,l_shoulder_roll,l_shoulder_yaw,l_elbow,l_wrist_pitch,l_wrist_yaw,r_shoulder_pitch,r_shoulder_roll,r_shoulder_yaw,r_elbow,r_wrist_pitch,r_wrist_yaw,l_hip_pitch,l_hip_roll,l_hip_yaw,l_knee,l_ankle_pitch,l_ankle_roll,r_hip_pitch,r_hip_roll,r_hip_yaw,r_knee,r_ankle_pitch,r_ankle_roll)</param>
<param name="modelFile">model.urdf</param>
<param name="fixedFrameGravity">(0,0,-9.81)</param>
<param name="defaultContactFrames">(l_hand_palm,r_hand_palm,root_link,l_foot_front,l_foot_rear,r_foot_front,r_foot_rear,l_upper_leg,r_upper_leg)</param>
<param name="imuFrameName">head_imu_0</param>
<param name="useJointVelocity">true</param>
<param name="useJointAcceleration">true</param>
<param name="imuFilterCutoffInHz">3.0</param>
<param name="forceTorqueFilterCutoffInHz">3.0</param>
<param name="jointVelFilterCutoffInHz">3.0</param> <!-- used if useJointVelocity is set to true -->
<param name="jointAccFilterCutoffInHz">3.0</param> <!-- used if useJointAcceleration is set to true -->
<param name="startWithZeroFTSensorOffsets">true</param> <!-- bypass using resetOffset of FT sensors in simulation -->
<param name="useSkinForContacts">false</param>
<param name="publishNetExternalWrenches">true</param>
<param name="disableSensorReadCheckAtStartup">true</param>

<group name="GRAVITY_COMPENSATION">
<param name="enableGravityCompensation">true</param>
<param name="gravityCompensationBaseLink">root_link</param>
<param name="gravityCompensationAxesNames">(torso_roll,torso_pitch,torso_yaw,l_shoulder_pitch,l_shoulder_roll,l_shoulder_yaw,l_elbow,r_shoulder_pitch,r_shoulder_roll,r_shoulder_yaw,r_elbow)</param>
</group>

<group name="HW_USE_MAS_IMU">
<param name="accelerometer">head_imu_0</param>
<param name="gyroscope">head_imu_0</param>
</group>

<group name="WBD_OUTPUT_EXTERNAL_WRENCH_PORTS">
<param name="/wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o">(l_foot_front,l_sole,l_sole)</param>
<param name="/wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o">(l_foot_rear,l_sole,l_sole)</param>
<param name="/wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o">(r_foot_front,r_sole,r_sole)</param>
<param name="/wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o">(r_foot_rear,r_sole,r_sole)</param>
<param name="/wholeBodyDynamics/left_arm/cartesianEndEffectorWrench:o">(l_hand_palm,l_hand_palm,root_link)</param>
<param name="/wholeBodyDynamics/right_arm/cartesianEndEffectorWrench:o">(r_hand_palm,r_hand_palm,root_link)</param>
</group>



<group name="multipleAnalogSensorsNames">
<param name="SixAxisForceTorqueSensorsNames">("l_arm_ft", "r_arm_ft", "l_leg_ft", "r_leg_ft", "l_foot_front_ft", "r_foot_front_ft", "l_foot_rear_ft", "r_foot_rear_ft")</param>
<!-- <param name="TemperatureSensorsNames">("l_arm_ft", "r_arm_ft", "l_leg_ft", "r_leg_ft")</param> -->
</group>


<action phase="startup" level="15" type="attach">
<paramlist name="networks">
<!-- motorcontrol -->
<elem name="left_leg">left_leg_mc</elem>
<elem name="right_leg">right_leg_mc</elem>
<elem name="torso">torso_mc</elem>
<elem name="right_arm">right_arm_mc</elem>
<elem name="left_arm">left_arm_mc</elem>
<!--elem name="right_lower_arm">right_arm-mc_wrapper</elem>
<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="left_arm_ft_sensor">ergocub_left_arm_ft</elem>
<elem name="right_arm_ft_sensor">ergocub_right_arm_ft</elem>
<elem name="left_leg_ft_sensor">ergocub_left_leg_ft</elem>
<elem name="right_leg_ft_sensor">ergocub_right_leg_ft</elem>
</paramlist>
</action>

<action phase="shutdown" level="2" type="detach" />

</device>
</devices>
51 changes: 51 additions & 0 deletions install/share/ergoCub/conf/gazebo_ergocub_head.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
disableImplicitNetworkWrapper
yarpDeviceName head_hardware_device

jointNames neck_pitch neck_roll neck_yaw camera_tilt

min_stiffness 0.0 0.0 0.0 0.0
max_stiffness 1000.0 1000.0 1000.0 1000.0
min_damping 0.0 0.0 0.0 0.0
max_damping 100.0 100.0 100.0 100.0
max_torques 1000000.0 1000000.0 1000000.0 1000000.0


#PIDs:
# this information is used to set the PID values in simulation for GAZEBO, we need only the first three values
[POSITION_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
kp 1.745 1.745 1.745 1.745
kd 0.122 0.122 0.122 0.122
ki 0.003 0.003 0.003 0.003
maxInt 9999 9999 9999 9999
maxOutput 9999 9999 9999 9999
shift 0.0 0.0 0.0 0.0
ko 0.0 0.0 0.0 0.0
stictionUp 0.0 0.0 0.0 0.0
stictionDwn 0.0 0.0 0.0 0.0

[VELOCITY_CONTROL]
velocityControlImplementationType integrator_and_position_pid
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
kp 8.726 8.726 8.726 8.726
kd 0.035 0.035 0.035 0.035
ki 0.003 0.003 0.003 0.003
maxInt 9999 9999 9999 9999
maxOutput 9999 9999 9999 9999
shift 0.0 0.0 0.0 0.0
ko 0.0 0.0 0.0 0.0
stictionUp 0.0 0.0 0.0 0.0
stictionDwn 0.0 0.0 0.0 0.0

[IMPEDANCE_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
stiffness 0.0 0.0 0.0 0.0
damping 0.0 0.0 0.0 0.0

[LIMITS]
jntPosMax 17.0 20.0 45.0 30.0
jntPosMin -30.0 -20.0 -45.0 -30
jntVelMax 100.0 100.0 100.0 100
2 changes: 2 additions & 0 deletions install/share/ergoCub/conf/gazebo_ergocub_inertial.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName head_inertial_hardware_device
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName l_foot_front_ft_sensor_inertial_hardware_device
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
disableImplicitNetworkWrapper
yarpDeviceName l_foot_rear_ft_sensor_inertial_hardware_device
53 changes: 53 additions & 0 deletions install/share/ergoCub/conf/gazebo_ergocub_left_arm.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
disableImplicitNetworkWrapper
yarpDeviceName left_arm_hardware_device

jointNames l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow l_wrist_yaw l_wrist_roll l_wrist_pitch

min_stiffness 0.0 0.0 0.0 0.0 0.0 0.0 0.0
max_stiffness 1000.0 1000.0 1000.0 1000.0 1000.0 1000.0 1000.0
min_damping 0.0 0.0 0.0 0.0 0.0 0.0 0.0
max_damping 100.0 100.0 100.0 100.0 100.0 100.0 100.0
max_torques 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0

[TRAJECTORY_GENERATION]
trajectory_type minimum_jerk

#PIDs:
# this information is used to set the PID values in simulation for GAZEBO, we need only the first three values
[POSITION_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
kp 5.745 5.745 5.745 1.745 1.745 1.745 1.745
kd 0.174 0.174 0.174 0.174 0.174 0.174 0.0
ki 0.174 0.174 0.174 0.174 0.174 0.174 0.0
maxInt 9999 9999 9999 9999 9999 9999 9999
maxOutput 9999 9999 9999 9999 9999 9999 9999
shift 0.0 0.0 0.0 0.0 0.0 0.0 0.0
ko 0.0 0.0 0.0 0.0 0.0 0.0 0.0
stictionUp 0.0 0.0 0.0 0.0 0.0 0.0 0.0
stictionDwn 0.0 0.0 0.0 0.0 0.0 0.0 0.0

[VELOCITY_CONTROL]
velocityControlImplementationType integrator_and_position_pid
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
kp 8.726 8.726 8.726 5.236 5.236 5.236 5.236
kd 0.035 0.035 0.035 0.002 0.002 0.002 0.0
ki 0.002 0.002 0.002 0.0 0.0 0.0 0.0
maxInt 9999 9999 9999 9999 9999 9999 9999
maxOutput 9999 9999 9999 9999 9999 9999 9999
shift 0.0 0.0 0.0 0.0 0.0 0.0 0.0
ko 0.0 0.0 0.0 0.0 0.0 0.0 0.0
stictionUp 0.0 0.0 0.0 0.0 0.0 0.0 0.0
stictionDwn 0.0 0.0 0.0 0.0 0.0 0.0 0.0

[IMPEDANCE_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
stiffness 0.0 0.0 0.0 0.0 0.0 0.0 0.0
damping 0.0 0.0 0.0 0.0 0.0 0.0 0.0

[LIMITS]
jntPosMax 20.0 160.0 80.0 75.0 90.0 50.0 30.0
jntPosMin -175.0 12.0 -50.0 -3.0 -90.0 -60.0 -30.0
jntVelMax 100.0 100.0 100.0 100.0 100.0 100.0 100.0
Loading

0 comments on commit 5c51248

Please sign in to comment.