Hi Andrew,

You are correct that applied forces are only "external user applied forces", and does not include any reaction or constraint holding forces based on physics (LCP result).  To implement what you have described (force&torque sensor), I think you can obtain that information by summing up external forces (gazebo_ros_f3d)
and the constraint forces provided by joints:
dJointFeedback *ODEJoint::GetFeedback().

does that sound about right?
John


On Thu, Jan 13, 2011 at 9:12 AM, Andy Somerville <andy.somerville@resquared.com> wrote:
John,

When you say it returns "applied forces" do you mean to say that it
does not return forces that are the result of the physics simulation,
and only returns forces that are the result of something like
"rosservice call gazebo/apply_body_wrench"?

My goal was to implement a force&torque sensor. In my setup, I applied
the plugin to one of the links in a 7 dof manipulator. My expectation
was that all of the forces and torques that occur in the simulation to
that link would be reported. Perhaps I misunderstood the purpose of
the plugin? If so, do you happen to know of a way to get the forces on
a target link?

    Andrew

On Wed, Jan 12, 2011 at 9:11 PM, John Hsu <johnhsu@willowgarage.com> wrote:
> Hi Andrew,
> gazebo_ros_f3d returns applied forces and I just checked with
> rosservice call gazebo/apply_body_wrench
> and rxplotted the topic, and things look as expected for me.  Can you
> describe more detail what your setup is?
> thanks,
> John
> On Wed, Jan 12, 2011 at 4:32 PM, Andy Somerville
> <andy.somerville@resquared.com> wrote:
>>
>> Hi,
>>
>> Has anyone had previous success with GazeboRosF3D in cturtle? In
>> attempting to use the GazeboRosF3D I've hit a bit of a wall. I believe
>> that I'm using it correctly and the topic is even being published to,
>> but I get all zeros back in situations that seem to clearly imply
>> there should be some forces and torques.
>>
>> My urdf entry looks like:
>>
>> <gazebo>
>>    <controller:gazebo_ros_f3d name="${side}_FTsensor"
>> plugin="libgazebo_ros_f3d.so">
>>        <alwaysOn>true</alwaysOn>
>>        <updateRate>100.0</updateRate>
>>        <bodyName>DarmSim/${side}Arm/WAM/LowerWristFTPalmLink</bodyName>
>>        <topicName>DarmSim/${side}Arm/WAM/Wrist/FTSensor</topicName>
>>        <frameName>DarmSim/${side}Arm/WAM/LowerWristFTPalmLink</frameName>
>>        <interface:position name="${side}_FTsensor_force_iface" />
>>    </controller:gazebo_ros_f3d>
>> </gazebo>
>>
>>
>> Where side is being filled in by "Left" and "Right", and
>> "DarmSim/${side}Arm/WAM/LowerWristFTPalmLink" is the name of a link
>> defined above the f3d entry in the xacro.
>>
>> Running the simulation produces the expected topics:
>>
>> /DarmSim/LeftArm/WAM/Wrist/FTSensor
>> /DarmSim/RightArm/WAM/Wrist/FTSensor
>>
>> But echoing them while performing an action that should clearly
>> produce a force and torque on that link consistently only produce 0s.
>>
>> I can find virtually no references to GazeboRosF3D being used in
>> google searches or in the stacks I have checked out with the one
>> exception being in
>> "pr2_common/pr2_description/urdf/gripper_v0/gripper.gazebo.xacro" but
>> that doesn't seem to be being subsequently used by anything. My next
>> step is to dive into the code behind GazeboRosF3D.
>>
>> Is anyone aware of some obvious factors that could explain the
>> behavior I'm seeing?
>>
>>     Andrew
>> _______________________________________________
>> ros-users mailing list
>> ros-users@code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>
>
> _______________________________________________
> ros-users mailing list
> ros-users@code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
>
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users