RethinkRobotics / baxter_simulator

Gazebo Simulation interface for the Baxter Research Robot
http://sdk.rethinkrobotics.com/wiki/Baxter_Simulator
BSD 3-Clause "New" or "Revised" License
84 stars 94 forks source link

Missing twist and wrench on endpoint_state topic #44

Open rethink-imcmahon opened 9 years ago

rethink-imcmahon commented 9 years ago

When running baxter_gazebo, no matter what is happening at the endpoint, there is no twist or wrench on the /robot/limb/left/endpoint_state topic:

# after launching gazebo in another teriminal
# via $ roslaunch baxter_gazebo baxter_world.launch
$ rostopic echo /robot/limb/left/endpoint_state

yields

header: 
  seq: 307258
  stamp: 
    secs: 0
    nsecs: 0
  frame_id: ''
pose: 
  position: 
    x: 0.572575815071
    y: 0.181186651371
    z: 0.24619470767
  orientation: 
    x: 0.140772189718
    y: 0.989644952796
    z: 0.0116515084487
    w: 0.0255009874122
twist: 
  linear: 
    x: 0.0
    y: 0.0
    z: 0.0
  angular: 
    x: 0.0
    y: 0.0
    z: 0.0
wrench: 
  force: 
    x: 0.0
    y: 0.0
    z: 0.0
  torque: 
    x: 0.0
    y: 0.0
    z: 0.0

---

regardless of the force acting on the end effector. This is due to the fact that neither of these were ever implemented.

IanTheEngineer commented 7 years ago

This is the relevant code segment: https://github.com/RethinkRobotics/baxter_simulator/blob/master/baxter_sim_kinematics/src/position_kinematics.cpp#L120-L134

void position_kinematics::FKCallback(const sensor_msgs::JointState msg) {
  baxter_core_msgs::EndpointState endpoint;

  sensor_msgs::JointState configuration;

  position_kinematics::FilterJointState(&msg, joint);
  //Copy the current Joint positions and names of the appropriate side to the configuration
  endpoint.pose = position_kinematics::FKCalc(joint).pose;

  //Fill out timestamp for endpoint
  endpoint.header.stamp = msg.header.stamp;

  //Publish the PoseStamp of the end effector
  end_pointstate_pub.publish(endpoint);
}

We need to use the forward kinematics of the joint efforts received in this JointState callback to calculate the wrench and twist in the endpoint frame.