Go to the documentation of this file.00001 #pragma once
00002
00003 #include <string>
00004 #include <vector>
00005 #include <map>
00006
00007 namespace shadow_robot_standalone
00008 {
00009
00010 struct JointState
00011 {
00012 JointState() :
00013 position(), velocity(), effort() {}
00014 JointState(double _position, double _velocity, double _effort) :
00015 position(_position), velocity(_velocity), effort(_effort) {}
00016 double position;
00017 double velocity;
00018 double effort;
00019 };
00020
00021 struct Tactile
00022 {
00023 int pac0;
00024 int pac1;
00025 int pdc;
00026
00027 int tac;
00028 int tdc;
00029
00030 static const int no_of_electrodes = 19;
00031 int electrodes[no_of_electrodes];
00032 };
00033
00034 enum ControlType
00035 {
00036 POSITION_PWM,
00037 EFFORT_TORQUE
00038 };
00039
00040 class ShadowHand
00041 {
00042 public:
00043 ShadowHand();
00044 ~ShadowHand();
00045
00054 bool get_control_type(ControlType & control_type);
00055
00064 bool set_control_type(ControlType control_type);
00065
00073 void send_position(const std::string &joint_name, double target);
00074
00082 void send_all_positions(const std::vector<double> &targets);
00083
00090 void send_torque(const std::string &joint_name, double target);
00091
00098 void send_all_torques(const std::vector<double> &targets);
00099
00107 std::map<std::string, JointState> & get_joint_states() const;
00114 std::vector<Tactile> & get_tactiles() const;
00115
00122 std::vector<std::string> get_controlled_joints() const;
00123
00130 std::vector<std::string> get_joints_with_state() const;
00131
00132 private:
00133
00134
00135
00136 class SrRosWrapper;
00137 SrRosWrapper *wrapper_;
00138 ShadowHand(const ShadowHand& other) {
00139 }
00140 ShadowHand& operator=(const ShadowHand& other) {
00141 }
00142 };
00143
00144 }