#include <test_joint_movement.hpp>
Public Member Functions | |
TestJointMovement (std::string joint_name, shadowrobot::HandCommander *hand_commander) | |
~TestJointMovement () | |
Public Attributes | |
double | mse |
std::map< std::string, std::vector< double > > | values |
Private Member Functions | |
std::string | get_ROS_topic_type (std::string topic_name) |
void | mse_cb_ (const std_msgs::Float64::ConstPtr &msg) |
void | sr_state_cb_ (const sr_robot_msgs::JointControllerState::ConstPtr &msg) |
void | state_cb_ (const control_msgs::JointControllerState::ConstPtr &msg) |
Private Attributes | |
boost::shared_ptr < shadowrobot::HandCommander > | hand_commander_ |
used with the sole purpose of knowing the name of the topic we want to subscribe to | |
std::string | joint_name_ |
ros::Subscriber | mse_sub_ |
boost::shared_ptr < shadowrobot::MovementFromImage > | mvt_from_img_ |
boost::shared_ptr < shadowrobot::MovementPublisher > | mvt_pub_ |
ros::NodeHandle | nh_tilde_ |
ros::Publisher | pub_ |
ros::Subscriber | sr_sub_state_ |
ros::Subscriber | sub_ |
ros::Subscriber | sub_state_ |
boost::shared_ptr< boost::thread > | thread_ |
Definition at line 40 of file test_joint_movement.hpp.
shadow_robot::TestJointMovement::TestJointMovement | ( | std::string | joint_name, |
shadowrobot::HandCommander * | hand_commander | ||
) |
Definition at line 35 of file test_joint_movement.cpp.
shadow_robot::TestJointMovement::~TestJointMovement | ( | ) | [inline] |
Definition at line 44 of file test_joint_movement.hpp.
std::string shadow_robot::TestJointMovement::get_ROS_topic_type | ( | std::string | topic_name | ) | [private] |
Definition at line 110 of file test_joint_movement.cpp.
void shadow_robot::TestJointMovement::mse_cb_ | ( | const std_msgs::Float64::ConstPtr & | msg | ) | [private] |
Definition at line 101 of file test_joint_movement.cpp.
void shadow_robot::TestJointMovement::sr_state_cb_ | ( | const sr_robot_msgs::JointControllerState::ConstPtr & | msg | ) | [private] |
Definition at line 87 of file test_joint_movement.cpp.
void shadow_robot::TestJointMovement::state_cb_ | ( | const control_msgs::JointControllerState::ConstPtr & | msg | ) | [private] |
Definition at line 94 of file test_joint_movement.cpp.
boost::shared_ptr<shadowrobot::HandCommander> shadow_robot::TestJointMovement::hand_commander_ [private] |
used with the sole purpose of knowing the name of the topic we want to subscribe to
Definition at line 72 of file test_joint_movement.hpp.
Definition at line 69 of file test_joint_movement.hpp.
Definition at line 44 of file test_joint_movement.hpp.
Definition at line 58 of file test_joint_movement.hpp.
boost::shared_ptr<shadowrobot::MovementFromImage> shadow_robot::TestJointMovement::mvt_from_img_ [private] |
Definition at line 62 of file test_joint_movement.hpp.
boost::shared_ptr<shadowrobot::MovementPublisher> shadow_robot::TestJointMovement::mvt_pub_ [private] |
Definition at line 63 of file test_joint_movement.hpp.
Definition at line 65 of file test_joint_movement.hpp.
Definition at line 51 of file test_joint_movement.hpp.
Definition at line 53 of file test_joint_movement.hpp.
Definition at line 50 of file test_joint_movement.hpp.
Definition at line 54 of file test_joint_movement.hpp.
boost::shared_ptr<boost::thread> shadow_robot::TestJointMovement::thread_ [private] |
Definition at line 67 of file test_joint_movement.hpp.
std::map<std::string, std::vector<double> > shadow_robot::TestJointMovement::values |
Definition at line 47 of file test_joint_movement.hpp.