Public Member Functions | Private Attributes
CobLookatController Class Reference

#include <cob_lookat_controller.h>

List of all members.

Public Member Functions

 CobLookatController ()
void initialize ()
void jointstate_cb (const sensor_msgs::JointState::ConstPtr &msg)
void lookatstate_cb (const sensor_msgs::JointState::ConstPtr &msg)
void run ()
void safety_stop_tracking ()
void twist_cb (const geometry_msgs::Twist::ConstPtr &msg)
 ~CobLookatController ()

Private Attributes

KDL::Chain chain_
std::string chain_base_
unsigned int chain_dof_
std::vector< std::string > chain_joints_
std::vector< float > chain_limits_vel_
std::string chain_tip_
ros::Publisher chain_vel_pub
std::string chain_vel_pub_topic_
ros::Subscriber jointstate_sub
KDL::JntArray last_q_
KDL::JntArray last_q_dot_
unsigned int lookat_dof_
std::vector< std::string > lookat_joints_
ros::Publisher lookat_vel_pub
ros::Subscriber lookatstate_sub
ros::NodeHandle nh_
KDL::ChainIkSolverVel_pinvp_iksolver_vel_
KDL::ChainIkSolverVel_wdlsp_iksolver_vel_wdls_
tf::TransformListener tf_listener_
unsigned int total_dof_
std::vector< std::string > total_joints_
ros::Subscriber twist_sub

Detailed Description

Definition at line 48 of file cob_lookat_controller.h.


Constructor & Destructor Documentation

Definition at line 81 of file cob_lookat_controller.h.


Member Function Documentation

get params

parse robot_description and set velocity limits

old stuff

parse robot_description and generate KDL chains

initialize configuration control solver

set weights for JointSpace

weight of joint 1 (R torso 1)

weight of joint 2 (R torso 2)

weight of joint 3 (R torso 3)

weight of joint 4 (P lookat 1)

weight of joint 5 (R lookat 2)

weight of joint 6 (R lookat 3)

weight of joint 7 (R lookat 4)

set weights for TaskSpace

set Lambda

initialize ROS interfaces

initialize variables and current joint values and velocities

Definition at line 39 of file cob_lookat_controller.cpp.

void CobLookatController::jointstate_cb ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 260 of file cob_lookat_controller.cpp.

void CobLookatController::lookatstate_cb ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 168 of file cob_lookat_controller.cpp.

Definition at line 330 of file cob_lookat_controller.cpp.

void CobLookatController::twist_cb ( const geometry_msgs::Twist::ConstPtr &  msg)

ToDo: Verify this transformation

Definition at line 175 of file cob_lookat_controller.cpp.


Member Data Documentation

Definition at line 61 of file cob_lookat_controller.h.

std::string CobLookatController::chain_base_ [private]

Definition at line 62 of file cob_lookat_controller.h.

unsigned int CobLookatController::chain_dof_ [private]

Definition at line 71 of file cob_lookat_controller.h.

std::vector<std::string> CobLookatController::chain_joints_ [private]

Definition at line 68 of file cob_lookat_controller.h.

std::vector<float> CobLookatController::chain_limits_vel_ [private]

Definition at line 74 of file cob_lookat_controller.h.

std::string CobLookatController::chain_tip_ [private]

Definition at line 63 of file cob_lookat_controller.h.

Definition at line 57 of file cob_lookat_controller.h.

Definition at line 59 of file cob_lookat_controller.h.

Definition at line 54 of file cob_lookat_controller.h.

Definition at line 76 of file cob_lookat_controller.h.

Definition at line 77 of file cob_lookat_controller.h.

unsigned int CobLookatController::lookat_dof_ [private]

Definition at line 72 of file cob_lookat_controller.h.

std::vector<std::string> CobLookatController::lookat_joints_ [private]

Definition at line 69 of file cob_lookat_controller.h.

Definition at line 58 of file cob_lookat_controller.h.

Definition at line 55 of file cob_lookat_controller.h.

Definition at line 51 of file cob_lookat_controller.h.

Definition at line 65 of file cob_lookat_controller.h.

Definition at line 66 of file cob_lookat_controller.h.

Definition at line 52 of file cob_lookat_controller.h.

unsigned int CobLookatController::total_dof_ [private]

Definition at line 73 of file cob_lookat_controller.h.

std::vector<std::string> CobLookatController::total_joints_ [private]

Definition at line 70 of file cob_lookat_controller.h.

Definition at line 56 of file cob_lookat_controller.h.


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


cob_lookat_controller
Author(s): Felix Messmer
autogenerated on Sun Mar 1 2015 13:56:32