Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes
shadowrobot::SrKinematics Class Reference

#include <sr_kinematics.h>

List of all members.

Public Member Functions

 SrKinematics ()
 ~SrKinematics ()

Private Types

typedef std::map< std::string,
double > 
JointsMap

Private Member Functions

geometry_msgs::PoseStamped getPoseFromTransform (tf::StampedTransform transform)
void jointstatesCallback (const sensor_msgs::JointStateConstPtr &msg)
bool loadModel (const std::string xml)
void reverseKinematicsCallback (const tf::tfMessageConstPtr &msg)
double toDegrees (double rad)

Private Attributes

std::string arm_kinematics_service
ros::Subscriber arm_subscriber
KDL::Chain chain
std::string fixed_frame
ros::Subscriber hand_subscriber
JointsMap joints_map
boost::mutex mutex
ros::NodeHandle n_tilde
ros::NodeHandle node
ros::Publisher pub_arm
ros::Publisher pub_hand
ros::ServiceClient rk_client
 The client for the reverse kinematics service implemented in arm_kinematics.
std::string rk_target
std::string root_name
tf::TransformListener tf_listener
 A transform listener used to get the transform between the reverse kinematics target and the root.
ros::Subscriber tf_sub
 The subscriber to the tf topic.
std::string tip_name

Static Private Attributes

static const std::string arm_joint_states_topic = "/sr_arm/position/joint_states"
static const std::string arm_sendupdate_topic = "/sr_arm/sendupdate"
static const std::string hand_joint_states_topic = "/srh/position/joint_states"
static const std::string hand_sendupdate_topic = "/srh/sendupdate"

Detailed Description

Definition at line 34 of file sr_kinematics.h.


Member Typedef Documentation

typedef std::map<std::string, double> shadowrobot::SrKinematics::JointsMap [private]

Definition at line 56 of file sr_kinematics.h.


Constructor & Destructor Documentation

init the connection to the arm kinematics inverse kinematics service

init the publisher on the topic /srh/sendupdate publishing messages of the type sr_hand::sendupdate.

Definition at line 33 of file sr_kinematics.cpp.

Definition at line 100 of file sr_kinematics.cpp.


Member Function Documentation

geometry_msgs::PoseStamped shadowrobot::SrKinematics::getPoseFromTransform ( tf::StampedTransform  transform) [private]

Convert the given transform to a pose.

In our case, the transform and the pose are equal as we're taking the transform from the origin.

Parameters:
transformTransform from the origin to the reverse kinematics target.
Returns:
Pose of the kinematics target.

Definition at line 227 of file sr_kinematics.cpp.

The callback for the joint_states topic. Periodically update the current position for the joints in the kinematic chain.

We can have the same callback for both joint_states subscribers: we're updating joints_map with data coming from both the hand and the arm.

Parameters:
msga JointState message

Definition at line 138 of file sr_kinematics.cpp.

bool shadowrobot::SrKinematics::loadModel ( const std::string  xml) [private]

Load the robot model and extract the correct joint_names from the kinematic chain, from root to tip.

Parameters:
xmlthe xml of the robot model
Returns:
true if success

Definition at line 104 of file sr_kinematics.cpp.

void shadowrobot::SrKinematics::reverseKinematicsCallback ( const tf::tfMessageConstPtr &  msg) [private]

compute the reverse kinematics for the kinematic chain between the specified root and the tip.

Parameters:
msga tf transform message

Definition at line 156 of file sr_kinematics.cpp.

double shadowrobot::SrKinematics::toDegrees ( double  rad) [inline, private]

Convert an angle in radians to an angle in degrees.

Parameters:
radthe angle in radians
Returns:
the value in degrees.

Definition at line 118 of file sr_kinematics.h.


Member Data Documentation

const std::string shadowrobot::SrKinematics::arm_joint_states_topic = "/sr_arm/position/joint_states" [static, private]

Definition at line 44 of file sr_kinematics.h.

the name of the link composing the root and the one of the tip of the kinematic chain

Definition at line 49 of file sr_kinematics.h.

const std::string shadowrobot::SrKinematics::arm_sendupdate_topic = "/sr_arm/sendupdate" [static, private]

Definition at line 44 of file sr_kinematics.h.

Definition at line 76 of file sr_kinematics.h.

contains the kinematic chain from root to tip

Definition at line 54 of file sr_kinematics.h.

Definition at line 49 of file sr_kinematics.h.

const std::string shadowrobot::SrKinematics::hand_joint_states_topic = "/srh/position/joint_states" [static, private]

Definition at line 44 of file sr_kinematics.h.

const std::string shadowrobot::SrKinematics::hand_sendupdate_topic = "/srh/sendupdate" [static, private]

Definition at line 44 of file sr_kinematics.h.

Definition at line 76 of file sr_kinematics.h.

A map containing the joints in the kinematic chain (from root to tip) and their current positions

Definition at line 60 of file sr_kinematics.h.

boost::mutex shadowrobot::SrKinematics::mutex [private]

Definition at line 70 of file sr_kinematics.h.

Definition at line 41 of file sr_kinematics.h.

Definition at line 41 of file sr_kinematics.h.

Definition at line 74 of file sr_kinematics.h.

Definition at line 74 of file sr_kinematics.h.

The client for the reverse kinematics service implemented in arm_kinematics.

Definition at line 101 of file sr_kinematics.h.

std::string shadowrobot::SrKinematics::rk_target [private]

Definition at line 49 of file sr_kinematics.h.

std::string shadowrobot::SrKinematics::root_name [private]

Definition at line 49 of file sr_kinematics.h.

A transform listener used to get the transform between the reverse kinematics target and the root.

Definition at line 98 of file sr_kinematics.h.

The subscriber to the tf topic.

Definition at line 96 of file sr_kinematics.h.

std::string shadowrobot::SrKinematics::tip_name [private]

Definition at line 49 of file sr_kinematics.h.


The documentation for this class was generated from the following files:


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Fri Jan 3 2014 12:03:25