#include <sr_ros_wrapper.hpp>
Public Member Functions | |
bool | get_control_type (ControlType ¤t_ctrl_type) |
void | joint0_state_cb (const sensor_msgs::JointStateConstPtr &msg) |
void | joint_state_cb (const sensor_msgs::JointStateConstPtr &msg) |
void | send_all_positions (const std::vector< double > &targets) |
void | send_all_torques (const std::vector< double > &targets) |
void | send_position (const std::string &joint_name, double target) |
void | send_torque (const std::string &joint_name, double target) |
bool | set_control_type (const ControlType &new_ctrl_type) |
void | spin (void) |
SrRosWrapper () | |
void | tactile_cb (const sr_robot_msgs::BiotacAllConstPtr &msg) |
Protected Attributes | |
boost::scoped_ptr < shadowrobot::HandCommander > | hand_commander_ |
ros::Subscriber | joint0_states_sub_ |
std::map< std::string, JointState > | joint_states_ |
ros::Subscriber | joint_states_sub_ |
boost::scoped_ptr < ros::NodeHandle > | n_tilde_ |
boost::scoped_ptr < ros::NodeHandle > | nh_ |
ros::Subscriber | tactile_sub_ |
std::vector< Tactile > | tactiles_ |
boost::unordered_map < std::string, ros::Publisher > | torque_pubs_ |
Friends | |
class | ShadowHand |
Definition at line 19 of file sr_ros_wrapper.hpp.
Definition at line 22 of file sr_ros_wrapper.cpp.
bool shadow_robot_standalone::ShadowHand::SrRosWrapper::get_control_type | ( | ControlType & | current_ctrl_type | ) |
Definition at line 63 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::joint0_state_cb | ( | const sensor_msgs::JointStateConstPtr & | msg | ) |
void shadow_robot_standalone::ShadowHand::SrRosWrapper::joint_state_cb | ( | const sensor_msgs::JointStateConstPtr & | msg | ) |
Definition at line 215 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::send_all_positions | ( | const std::vector< double > & | targets | ) |
Definition at line 153 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::send_all_torques | ( | const std::vector< double > & | targets | ) |
Definition at line 193 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::send_position | ( | const std::string & | joint_name, |
double | target | ||
) |
Definition at line 138 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::send_torque | ( | const std::string & | joint_name, |
double | target | ||
) |
Definition at line 179 of file sr_ros_wrapper.cpp.
bool shadow_robot_standalone::ShadowHand::SrRosWrapper::set_control_type | ( | const ControlType & | new_ctrl_type | ) |
Definition at line 86 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::spin | ( | void | ) |
Definition at line 54 of file sr_ros_wrapper.cpp.
void shadow_robot_standalone::ShadowHand::SrRosWrapper::tactile_cb | ( | const sr_robot_msgs::BiotacAllConstPtr & | msg | ) |
Definition at line 221 of file sr_ros_wrapper.cpp.
friend class ShadowHand [friend] |
Definition at line 21 of file sr_ros_wrapper.hpp.
boost::scoped_ptr<shadowrobot::HandCommander> shadow_robot_standalone::ShadowHand::SrRosWrapper::hand_commander_ [protected] |
Definition at line 45 of file sr_ros_wrapper.hpp.
Definition at line 47 of file sr_ros_wrapper.hpp.
std::map<std::string, JointState> shadow_robot_standalone::ShadowHand::SrRosWrapper::joint_states_ [protected] |
Definition at line 39 of file sr_ros_wrapper.hpp.
Definition at line 47 of file sr_ros_wrapper.hpp.
boost::scoped_ptr<ros::NodeHandle> shadow_robot_standalone::ShadowHand::SrRosWrapper::n_tilde_ [protected] |
Definition at line 43 of file sr_ros_wrapper.hpp.
boost::scoped_ptr<ros::NodeHandle> shadow_robot_standalone::ShadowHand::SrRosWrapper::nh_ [protected] |
Definition at line 42 of file sr_ros_wrapper.hpp.
Definition at line 48 of file sr_ros_wrapper.hpp.
std::vector<Tactile> shadow_robot_standalone::ShadowHand::SrRosWrapper::tactiles_ [protected] |
Definition at line 40 of file sr_ros_wrapper.hpp.
boost::unordered_map<std::string, ros::Publisher> shadow_robot_standalone::ShadowHand::SrRosWrapper::torque_pubs_ [protected] |
Definition at line 49 of file sr_ros_wrapper.hpp.