Public Member Functions | Private Member Functions | Private Attributes
r2_gaze_controller::R2GazeController Class Reference

#include <r2_gaze_controller.hpp>

List of all members.

Public Member Functions

bool initialize ()
 R2GazeController (const ros::NodeHandle &handle, const std::string &rootName, const std::string &tipName)
 ~R2GazeController ()

Private Member Functions

KDL::Segment createVirtualSegment ()
double getWeight (const std::string &paramName)
Eigen::MatrixXd getWeightMatrix ()
void look_at_cb (const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
void publishNeckCmd (const KDL::JntArray &q_cmd)
void serializeToMsg (const KDL::JntArray &q, sensor_msgs::JointState &cmdMsg)
void setupRosTopics (const std::string &lookAtTopicName, const std::string &neckJointCmdTopicName)
void transformToRootFrame (const geometry_msgs::PoseStamped::ConstPtr &pose_msg, KDL::Frame &frame)

Private Attributes

KDL::Frame F_desired
boost::scoped_ptr
< r2_gaze_controller::R2GazeIK
ikPtr
sensor_msgs::JointState jntCmdMsg
ros::Subscriber jointStateSubscriber
boost::scoped_ptr
< tf::MessageFilter
< geometry_msgs::PoseStamped > > 
lookAtFilter
message_filters::Subscriber
< geometry_msgs::PoseStamped > 
lookAtSubscriber
ros::Publisher neckCmdPublisher
ros::NodeHandle nodeHandle
KDL::JntArray q_cmd
KDL::JntArray q_init
std::string rootName
std::string tipName
tf::TransformListener transformListener

Detailed Description

Definition at line 29 of file r2_gaze_controller.hpp.


Constructor & Destructor Documentation

r2_gaze_controller::R2GazeController::R2GazeController ( const ros::NodeHandle handle,
const std::string &  rootName,
const std::string &  tipName 
)

Definition at line 32 of file r2_gaze_controller.cpp.

Definition at line 49 of file r2_gaze_controller.cpp.


Member Function Documentation

Definition at line 80 of file r2_gaze_controller.cpp.

double r2_gaze_controller::R2GazeController::getWeight ( const std::string &  paramName) [private]

Definition at line 87 of file r2_gaze_controller.cpp.

Definition at line 99 of file r2_gaze_controller.cpp.

Definition at line 54 of file r2_gaze_controller.cpp.

void r2_gaze_controller::R2GazeController::look_at_cb ( const geometry_msgs::PoseStamped::ConstPtr &  pose_msg) [private]

Definition at line 152 of file r2_gaze_controller.cpp.

void r2_gaze_controller::R2GazeController::publishNeckCmd ( const KDL::JntArray &  q_cmd) [private]

Definition at line 146 of file r2_gaze_controller.cpp.

void r2_gaze_controller::R2GazeController::serializeToMsg ( const KDL::JntArray &  q,
sensor_msgs::JointState &  cmdMsg 
) [private]

Definition at line 129 of file r2_gaze_controller.cpp.

void r2_gaze_controller::R2GazeController::setupRosTopics ( const std::string &  lookAtTopicName,
const std::string &  neckJointCmdTopicName 
) [private]

Definition at line 115 of file r2_gaze_controller.cpp.

void r2_gaze_controller::R2GazeController::transformToRootFrame ( const geometry_msgs::PoseStamped::ConstPtr &  pose_msg,
KDL::Frame frame 
) [private]

Definition at line 134 of file r2_gaze_controller.cpp.


Member Data Documentation

Definition at line 63 of file r2_gaze_controller.hpp.

Definition at line 56 of file r2_gaze_controller.hpp.

sensor_msgs::JointState r2_gaze_controller::R2GazeController::jntCmdMsg [private]

Definition at line 64 of file r2_gaze_controller.hpp.

Definition at line 49 of file r2_gaze_controller.hpp.

boost::scoped_ptr<tf::MessageFilter<geometry_msgs::PoseStamped> > r2_gaze_controller::R2GazeController::lookAtFilter [private]

Definition at line 52 of file r2_gaze_controller.hpp.

Definition at line 51 of file r2_gaze_controller.hpp.

Definition at line 50 of file r2_gaze_controller.hpp.

Definition at line 48 of file r2_gaze_controller.hpp.

Definition at line 62 of file r2_gaze_controller.hpp.

Definition at line 62 of file r2_gaze_controller.hpp.

Definition at line 59 of file r2_gaze_controller.hpp.

Definition at line 59 of file r2_gaze_controller.hpp.

Definition at line 53 of file r2_gaze_controller.hpp.


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


r2_controllers_gazebo
Author(s): Stephen Hart
autogenerated on Thu Jan 2 2014 11:31:58