shadow_hand.cpp
Go to the documentation of this file.
00001 #include "sr_standalone/shadow_hand.hpp"
00002 #include "sr_standalone/sr_ros_wrapper.hpp"
00003 
00004 using namespace std;
00005 
00006 namespace shadow_robot_standalone
00007 {
00008 
00009 ShadowHand::ShadowHand()
00010   : wrapper_(new SrRosWrapper()) {}
00011 
00012 ShadowHand::~ShadowHand()
00013 {
00014   delete wrapper_;
00015 }
00016 
00017 bool ShadowHand::get_control_type(ControlType & control_type)
00018 {
00019   return wrapper_->get_control_type(control_type);
00020 }
00021 
00022 bool ShadowHand::set_control_type(ControlType control_type)
00023 {
00024   return wrapper_->set_control_type(control_type);
00025 }
00026 
00027 void ShadowHand::send_position(const string &joint_name, double target)
00028 {
00029   wrapper_->send_position(joint_name, target);
00030 }
00031 
00032 void ShadowHand::send_all_positions(const vector<double> &targets)
00033 {
00034   wrapper_->send_all_positions(targets);
00035 }
00036 
00037 void ShadowHand::send_torque(const string &joint_name, double target)
00038 {
00039   wrapper_->send_torque(joint_name, target);
00040 }
00041 
00042 void ShadowHand::send_all_torques(const vector<double> &targets)
00043 {
00044   wrapper_->send_all_torques(targets);
00045 }
00046 
00047 map<string, JointState> & ShadowHand::get_joint_states() const
00048 {
00049   wrapper_->spin();
00050   return wrapper_->joint_states_;
00051 }
00052 
00053 vector<Tactile> & ShadowHand::get_tactiles() const
00054 {
00055   wrapper_->spin();
00056   return wrapper_->tactiles_;
00057 }
00058 
00059 vector<string> ShadowHand::get_joints_with_state() const
00060 {
00061   vector<string> joints_with_state;
00062   map<string, JointState>::const_iterator it = wrapper_->joint_states_.begin();
00063   while (it != wrapper_->joint_states_.end())
00064   {
00065     joints_with_state.push_back(it->first);
00066     ++it;
00067   }
00068   return joints_with_state;
00069 }
00070 
00071 vector<string> ShadowHand::get_controlled_joints() const
00072 {
00073   vector<string> controlled_joints;
00074   boost::unordered_map<string, ros::Publisher>::const_iterator it = wrapper_->torque_pubs_.begin();
00075   while (it != wrapper_->torque_pubs_.end())
00076   {
00077     controlled_joints.push_back(it->first);
00078     ++it;
00079   }
00080   return controlled_joints;
00081 }
00082 
00083 } // namespace


sr_standalone
Author(s): Manos Nikolaidis , Yi Li
autogenerated on Fri Aug 28 2015 13:10:49