Overview

This package estimates the wrenches exerted at the tip of the PR2 arms through two methods.

The first approach uses the joint efforts as input and propagates them forward using the inverse of the transposed jacobian.

The second approach takes the joint velocity errors as inputs and propagates the error forward through the jacobian to obtain the error in the twist of the tip of the arm. This error in the twist is a measure of the wrench up to a scale factor.

Filtered versions of the calculated signals through a Butterworth 2nd order LPF are also available.

The first method takes the joint efforts from the /joint_states topic, while the second needs to have joint velocity controllers loaded.

The configuration of the root and tip links of each arm are in the yaml files located in the config/ directory.

ROS API

l_arm_wrench_estimation/r_arm_wrench_estimation

Subscribed Topics

/joint_states (sensor_msgs/JointState)
  • Joint state information of the robot. From this topic the /field is used for
/l_arm_vel/state or /r_arm_vel/state (pr2_controllers_msgs/JointTrajectoryControllerState)
  • Receives joint positions and velocity error from the joint velocity controllers. Used for the second method described above.

Published Topics

/l_arm_wrench_estimation/estimated_wrench (geometry_msgs/WrenchStamped)
  • estimated wrench from the joint efforts.
/l_arm_wrench_estimation/filtered_wrench (geometry_msgs/WrenchStamped)
  • low pass filtered estimated wrench from joint efforts.
/l_arm_wrench_estimation/twist_error (geometry_msgs/TwistStamped)
  • error in the twist at the tip of the PR2 arm, calculated from the velocity error of the PR2's velocity controllers.
/l_arm_wrench_estimation/filtered_twist_error (geometry_msgs/TwistStamped)
  • low pass filtered estimated twist error at the tip of the PR2 arm.

Parameters

chain_tip_frame (string, default: "l_gripper_tool_frame")
  • Specifies the tip frame of the PR2 arm chain.
chain_root_frame (string, default: "torso_lift_link")
  • Specifies the root frame of the PR2 arm chain.
filter_coeff_b_effort (list of doubles, default: Required)
  • 3 element array specifying the 'b' coefficients of the LPF for the joint effort based wrench estimator.
filter_coeff_a_effort (list of doubles, default: Required)
  • 3 element array specifying the 'a' coefficients of the LPF for the joint effort based wrench estimator. The first element should be '1'.
filter_coeff_b_vel (list of doubles, default: Required)
  • 3 element array specifying the 'b' coefficients of the LPF for the joint velocity error based wrench estimator.
filter_coeff_a_vel (list of doubles, default: Required)
  • 3 element array specifying the 'a' coefficients of the LPF for the joint velocity error based wrench estimator. The first element should be '1'.

Wiki: pr2_wrench_estimation (last edited 2013-04-23 16:51:56 by FranciscoVina)