ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I have solved it
1) urdf I add ft_sensor in the foot <xacro:macro name="gazebo_pressure" params="prefix parent num x y z"> <link name="${prefix}_foot_sensor_m${num}" >="" <inertial=""> <origin xyz="0 0 0" rpy="0 0 0"/> <mass value="0.01"/> <inertia ixx="0.000" ixy="0.000" ixz="0.000" iyy="0.000" iyz="0.000" izz="0.000"/> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.025 0.025 0.002"/> </geometry> <material name=""> <color rgba="0.75294 0.75294 0.75294 1"/> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.025 0.025 0.002"/> </geometry> </collision> </link> <joint name="${prefix}_foot_sensor_m${num}_j" type="revolute"> <origin xyz="${x} ${y} ${z}" rpy="0 0 0"/> <parent link="${parent}"/> <child link="${prefix}_foot_sensor_m${num}"/> <axis xyz="0 1 0"/> <limit effort="0" velocity="0" lower="-0.001" upper="0.001"/> </joint> <gazebo reference="${prefix}_foot_sensor_m${num}_j"> <providefeedback>true</providefeedback> </gazebo>
<gazebo> <plugin name="ft_sensor" filename="libgazebo_ros_ft_sensor.so"> <always_on>true</always_on> <updaterate>100.0</updaterate> <topicname>/leap_one/${prefix}_foot_sensor_m${num}</topicname> <jointname>${prefix}_foot_sensor_m${num}_j</jointname> </plugin> </gazebo>
<gazebo reference="${prefix}_foot_sensor_m${num}"> <material>Gazebo/Blue</material> <mu1>9000</mu1> <mu2>9000</mu2> <kp>1000000.0</kp> <kd>10.0</kd> <mindepth>0.001</mindepth> <maxcontacts>100</maxcontacts> </gazebo>
</xacro:macro>
<xacro:gazebo_pressure prefix="left" parent="left_m6" num="0" x="-0.03" y="-0.03" z="-0.034"/> <xacro:gazebo_pressure prefix="left" parent="left_m6" num="1" x="0.03" y="-0.03" z="-0.034"/> <xacro:gazebo_pressure prefix="left" parent="left_m6" num="2" x="-0.03" y="0.03" z="-0.034"/> <xacro:gazebo_pressure prefix="left" parent="left_m6" num="3" x="0.03" y="0.03" z="-0.034"/>
<xacro:gazebo_pressure prefix="right" parent="right_m6" num="0" x="-0.03" y="-0.03" z="-0.034"/> <xacro:gazebo_pressure prefix="right" parent="right_m6" num="1" x="0.03" y="-0.03" z="-0.034"/> <xacro:gazebo_pressure prefix="right" parent="right_m6" num="2" x="-0.03" y="0.03" z="-0.034"/> <xacro:gazebo_pressure prefix="right" parent="right_m6" num="3" x="0.03" y="0.03" z="-0.034"/>
2) modify ros source code clone gazebo_ros_pkgs repository in github add one line in the gazebo_plugins/src/gazebo_ros_ft_sensor.cpp
//////////////////////////////////////////////////////////////////////////////// // Update the controller void GazeboRosFT::UpdateChild() {
common::Time cur_time = this->world_->SimTime();
common::Time cur_time = this->world_->GetSimTime();
// rate control if (this->update_rate_ > 0 && (cur_time-this->last_time_).Double() < (1.0/this->update_rate_)) { +++ if(cur_time.Double() >= 5) // ignore it when reset_simulation return; }
if (this->ft_connect_count_ == 0) return;
physics::JointWrench wrench; ignition::math::Vector3d torque; ignition::math::Vector3d force;
// FIXME: Should include options for diferent frames and measure directions // E.g: https://bitbucket.org/osrf/gazebo/raw/default/gazebo/sensors/ForceTorqueSensor.hh // Get force torque at the joint // The wrench is reported in the CHILD <frame> // The <measure_direction> is child_to_parent wrench = this->joint_->GetForceTorque(0);
force = wrench.body2Force; torque = wrench.body2Torque;
force = wrench.body2Force.Ign(); torque = wrench.body2Torque.Ign();
then catkin_make and cp devel/lib/libgazebo_ros_ft_sensor.so into /opt/ros/kinetic/lib/
2 | No.2 Revision |
I have solved it
1) urdf
I add ft_sensor in the foot
foot
<xacro:macro name="gazebo_pressure" params="prefix parent num x y z">
<link name="${prefix}_foot_sensor_m${num}" >="" <inertial="">
<origin >
<inertial>
<origin
xyz="0 0 0" 0"
rpy="0 0 0"/>
<mass value="0.01"/>
<inertia ixx="0.000" ixy="0.000" ixz="0.000" iyy="0.000" iyz="0.000" izz="0.000"/>
0" />
<mass
value="0.01" />
<inertia
ixx="0.000"
ixy="0.000"
ixz="0.000"
iyy="0.000"
iyz="0.000"
izz="0.000" />
</inertial>
<visual>
<origin <origin
xyz="0 0 0" 0"
rpy="0 0 0"/>
0" />
<geometry>
<box size="0.025 0.025 0.002"/>
</geometry>
<material <material
name="">
<color <color
rgba="0.75294 0.75294 0.75294 1"/>
1" />
</material>
</visual>
<collision>
<origin <origin
xyz="0 0 0" 0"
rpy="0 0 0"/>
0" />
<geometry>
<box size="0.025 0.025 0.002"/>
</geometry>
</collision>
</link>
<joint name="${prefix}_foot_sensor_m${num}_j"
name="${prefix}_foot_sensor_m${num}_j"
type="revolute">
<origin <origin
xyz="${x} ${y} ${z}" ${z}"
rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="${prefix}_foot_sensor_m${num}"/>
<axis 0" />
<parent
link="${parent}" />
<child
link="${prefix}_foot_sensor_m${num}" />
<axis
xyz="0 1 0"/>
0" />
<limit effort="0" velocity="0" lower="-0.001" upper="0.001"/>
upper="0.001" />
</joint>
<gazebo reference="${prefix}_foot_sensor_m${num}_j">
<providefeedback>true</providefeedback>
</gazebo> <provideFeedback>true</provideFeedback>
</gazebo>
<gazebo>
<plugin name="ft_sensor" filename="libgazebo_ros_ft_sensor.so">
<always_on>true</always_on>
<updaterate>100.0</updaterate>
<topicname>/leap_one/${prefix}_foot_sensor_m${num}</topicname>
<jointname>${prefix}_foot_sensor_m${num}_j</jointname>
<updateRate>100.0</updateRate>
<topicName>/leap_one/${prefix}_foot_sensor_m${num}</topicName>
<jointName>${prefix}_foot_sensor_m${num}_j</jointName>
</plugin>
</gazebo> </gazebo>
<gazebo reference="${prefix}_foot_sensor_m${num}">
<material>Gazebo/Blue</material>
<mu1>9000</mu1>
<mu2>9000</mu2>
<kp>1000000.0</kp>
<kd>10.0</kd>
<mindepth>0.001</mindepth>
<maxcontacts>100</maxcontacts>
</gazebo> </xacro:macro>
<minDepth>0.001</minDepth>
<maxContacts>100</maxContacts>
</gazebo>
</xacro:macro>
<xacro:gazebo_pressure prefix="left" parent="left_m6" num="0" x="-0.03" y="-0.03" z="-0.034"/>
z="-0.034" />
<xacro:gazebo_pressure prefix="left" parent="left_m6" num="1" x="0.03" y="-0.03" z="-0.034"/>
z="-0.034" />
<xacro:gazebo_pressure prefix="left" parent="left_m6" num="2" x="-0.03" y="0.03" z="-0.034"/>
z="-0.034" />
<xacro:gazebo_pressure prefix="left" parent="left_m6" num="3" x="0.03" y="0.03" z="-0.034"/> z="-0.034" />
<xacro:gazebo_pressure prefix="right" parent="right_m6" num="0" x="-0.03" y="-0.03" z="-0.034"/>
z="-0.034" />
<xacro:gazebo_pressure prefix="right" parent="right_m6" num="1" x="0.03" y="-0.03" z="-0.034"/>
z="-0.034" />
<xacro:gazebo_pressure prefix="right" parent="right_m6" num="2" x="-0.03" y="0.03" z="-0.034"/>
z="-0.034" />
<xacro:gazebo_pressure prefix="right" parent="right_m6" num="3" x="0.03" y="0.03" z="-0.034"/>z="-0.034" />
2) modify ros source code clone gazebo_ros_pkgs repository in github add one line in the gazebo_plugins/src/gazebo_ros_ft_sensor.cpp
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosFT::UpdateChild()
then catkin_make and cp devel/lib/libgazebo_ros_ft_sensor.so into /opt/ros/kinetic/lib/