sr_ros_wrapper.hpp
Go to the documentation of this file.
00001 #pragma once
00002 
00003 #include "sr_standalone/shadow_hand.hpp"
00004 #include <boost/scoped_ptr.hpp>
00005 #include <boost/unordered_map.hpp>
00006 #include <ros/ros.h>
00007 #include <sensor_msgs/JointState.h>
00008 #include <sr_hand/hand_commander.hpp>
00009 #include <sr_robot_msgs/ControlType.h>
00010 #include <sr_robot_msgs/ChangeControlType.h>
00011 #include <sr_robot_msgs/ChangeControlTypeRequest.h>
00012 #include <sr_robot_msgs/ChangeControlTypeResponse.h>
00013 #include <sr_robot_msgs/BiotacAll.h>
00014 #include <sr_robot_msgs/joint.h>
00015 
00016 namespace shadow_robot_standalone
00017 {
00018 
00019 class ShadowHand::SrRosWrapper
00020 {
00021   friend class ShadowHand;
00022 public:
00023   SrRosWrapper();
00024 
00025   bool get_control_type(ControlType &current_ctrl_type);
00026   bool set_control_type(const ControlType &new_ctrl_type);
00027 
00028   void send_position(const std::string &joint_name, double target);
00029   void send_all_positions(const std::vector<double> &targets);
00030   void send_torque(const std::string &joint_name, double target);
00031   void send_all_torques(const std::vector<double> &targets);
00032   void spin(void);
00033 
00034   void joint_state_cb(const sensor_msgs::JointStateConstPtr &msg);
00035   void joint0_state_cb(const sensor_msgs::JointStateConstPtr &msg);
00036   void tactile_cb(const sr_robot_msgs::BiotacAllConstPtr &msg);
00037 
00038 protected:
00039   std::map<std::string, JointState> joint_states_;
00040   std::vector<Tactile> tactiles_;
00041 
00042   boost::scoped_ptr<ros::NodeHandle> nh_;
00043   boost::scoped_ptr<ros::NodeHandle> n_tilde_;
00044 
00045   boost::scoped_ptr<shadowrobot::HandCommander> hand_commander_;
00046 
00047   ros::Subscriber joint_states_sub_, joint0_states_sub_;
00048   ros::Subscriber tactile_sub_;
00049   boost::unordered_map<std::string, ros::Publisher> torque_pubs_;
00050 };
00051 
00052 } // namespace


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