00001
00030 #ifndef SHADOWHAND_H_
00031 # define SHADOWHAND_H_
00032
00033 #include <ros/ros.h>
00034 #include <string>
00035 #include <vector>
00036 #include <map>
00037
00038 #include <boost/smart_ptr.hpp>
00039 #include <boost/thread.hpp>
00040
00041 #ifdef GAZEBO
00042 #include <sensor_msgs/JointState.h>
00043 #endif
00044
00045 namespace shadowrobot
00046 {
00050 struct JointData
00051 {
00052 double position;
00053 double target;
00054 double temperature;
00055 double current;
00056 double force;
00057 std::string flags;
00058 int jointIndex;
00059 double min;
00060 double max;
00061 short isJointZero;
00062 #ifdef GAZEBO
00063
00068 int publisher_index;
00069 #endif
00070 ros::Time last_pos_time;
00071 double last_pos;
00072 double velocity;
00073
00074
00075
00076 #ifdef GAZEBO
00077 JointData() :
00078 position(0.0), target(0.0), temperature(0.0), current(0.0), force(0.0), flags(""), jointIndex(0), min(0.0), max(90.0), isJointZero(0), publisher_index(0), last_pos_time(0.0), last_pos(0.0), velocity(0.0)
00079 {
00080 }
00081
00082 JointData(JointData& jd) :
00083 position(jd.position), target(jd.target), temperature(jd.temperature), current(jd.current), force(jd.force),
00084 flags(jd.flags), jointIndex(jd.jointIndex), min(jd.min), max(jd.max), isJointZero(jd.isJointZero), publisher_index(jd.publisher_index), last_pos_time(jd.last_pos_time), last_pos(jd.last_pos), velocity(jd.velocity)
00085 {
00086 }
00087
00088 JointData(const JointData& jd) :
00089 position(jd.position), target(jd.target), temperature(jd.temperature), current(jd.current), force(jd.force),
00090 flags(jd.flags), jointIndex(jd.jointIndex), min(jd.min), max(jd.max), isJointZero(jd.isJointZero), publisher_index(jd.publisher_index), last_pos_time(jd.last_pos_time), last_pos(jd.last_pos), velocity(jd.velocity)
00091 {
00092 }
00093 #else
00094 JointData() :
00095 position(0.0), target(0.0), temperature(0.0), current(0.0), force(0.0), flags(""), jointIndex(0), min(0.0), max(90.0), isJointZero(0), last_pos_time(0.0), last_pos(0.0), velocity(0.0)
00096 {
00097 }
00098
00099 JointData( JointData& jd ) :
00100 position(jd.position), target(jd.target), temperature(jd.temperature), current(jd.current), force(jd.force), flags(jd.flags), jointIndex(jd.jointIndex), min(jd.min), max(jd.max),
00101 isJointZero(jd.isJointZero), last_pos_time(jd.last_pos_time), last_pos(jd.last_pos), velocity(jd.velocity)
00102 {
00103 }
00104
00105 JointData( const JointData& jd ) :
00106 position(jd.position), target(jd.target), temperature(jd.temperature), current(jd.current), force(jd.force), flags(jd.flags), jointIndex(jd.jointIndex), min(jd.min), max(jd.max),
00107 isJointZero(jd.isJointZero), last_pos_time(jd.last_pos_time), last_pos(jd.last_pos), velocity(jd.velocity)
00108 {
00109 }
00110 #endif
00111
00112 };
00113
00117 enum controller_parameters
00118 {
00119 PARAM_sensor,
00120 PARAM_target,
00121 PARAM_valve,
00122 PARAM_deadband,
00123 PARAM_p,
00124 PARAM_i,
00125 PARAM_d,
00126 PARAM_imax,
00127 PARAM_output_offset,
00128 PARAM_shift,
00129 PARAM_output_max,
00130
00131 PARAM_motor_maxforce,
00132 PARAM_motor_safeforce,
00133 PARAM_force_p,
00134 PARAM_force_i,
00135 PARAM_force_d,
00136 PARAM_force_imax,
00137 PARAM_force_out_shift,
00138 PARAM_force_deadband,
00139 PARAM_force_offset,
00140 PARAM_sensor_imax,
00141 PARAM_sensor_out_shift,
00142 PARAM_sensor_deadband,
00143 PARAM_sensor_offset,
00144 PARAM_max_temperature,
00145 PARAM_max_current,
00146 PARAM_type_of_sensor,
00147 PARAM_type_of_setpoint
00149
00150 };
00151
00155 struct Parameters
00156 {
00158 std::string name;
00160 std::string value;
00161
00162 Parameters() :
00163 name(""), value("")
00164 {
00165 }
00166
00167 Parameters( Parameters& param ) :
00168 name(param.name), value(param.value)
00169 {
00170 }
00171
00172 Parameters( const Parameters& param ) :
00173 name(param.name), value(param.value)
00174 {
00175 }
00176 };
00177
00181 struct JointControllerData
00182 {
00183 std::vector<Parameters> data;
00184
00185 JointControllerData() :
00186 data()
00187 {
00188 }
00189
00190 JointControllerData( JointControllerData& jcd ) :
00191 data(jcd.data)
00192 {
00193 }
00194
00195 JointControllerData( const JointControllerData& jcd ) :
00196 data(jcd.data)
00197 {
00198 }
00199 };
00200
00204 struct DiagnosticData
00205 {
00207 std::string joint_name;
00209 short level;
00210
00212 std::string flags;
00213
00215 int target_sensor_num;
00217 double target;
00218
00220 int position_sensor_num;
00222 double position;
00223
00225 double temperature;
00227 double current;
00229 double force;
00230 };
00231
00239 class SRArticulatedRobot
00240 {
00241 public:
00245 SRArticulatedRobot()
00246 {
00247 }
00248 ;
00249
00253 ~SRArticulatedRobot()
00254 {
00255 }
00256 ;
00257
00259 typedef std::map<std::string, JointData> JointsMap;
00261 typedef std::map<std::string, enum controller_parameters> ParametersMap;
00262
00269 virtual short sendupdate( std::string joint_name, double target ) = 0;
00270
00276 virtual JointData getJointData( std::string joint_name ) = 0;
00277
00282 virtual JointsMap getAllJointsData() = 0;
00283
00290 virtual short setContrl( std::string contrlr_name, JointControllerData ctrlr_data ) = 0;
00291
00297 virtual JointControllerData getContrl( std::string contrlr_name ) = 0;
00298
00306 virtual short setConfig( std::vector<std::string> myConfig ) = 0;
00307
00314 virtual void getConfig( std::string joint_name ) = 0;
00315
00320 virtual std::vector<DiagnosticData> getDiagnostics() = 0;
00321
00323 JointsMap joints_map;
00324
00326 ParametersMap parameters_map;
00327
00328 boost::mutex joints_map_mutex;
00329 boost::mutex parameters_map_mutex;
00330 boost::mutex controllers_map_mutex;
00331
00332 protected:
00333
00334 #ifdef GAZEBO
00335 std::vector<ros::Publisher> gazebo_publishers;
00336 ros::Subscriber gazebo_subscriber;
00337 #endif
00338 };
00339
00340 }
00341
00342 #endif