sr_actuator.hpp
Go to the documentation of this file.
00001 
00027 #ifndef _SR_ACTUATOR_HPP_
00028 #define _SR_ACTUATOR_HPP_
00029 
00030 #include "sr_hardware_interface/tactile_sensors.hpp"
00031 #include <ros_ethercat_model/hardware_interface.hpp>
00032 
00033 namespace sr_actuator
00034 {
00035 
00036 class SrActuatorState
00037 {
00038 public:
00039   SrActuatorState() :
00040     position_unfiltered_(0.0),
00041     can_msgs_received_(0),
00042     can_msgs_transmitted_(0),
00043     pic_firmware_svn_revision_(0),
00044     server_firmware_svn_revision_(0),
00045     firmware_modified_(0),
00046     serial_number_low_set(false),
00047     serial_number_high_set(false),
00048     serial_number_low(0),
00049     serial_number_high(0),
00050     serial_number(0),
00051     assembly_data_year(0),
00052     assembly_data_month(0),
00053     assembly_data_day(0),
00054     tests_(0),
00055     can_error_counters(0)
00056   {
00057   }
00058 
00059   //Serial number is composed of a low and a high byte.
00060   void set_serial_number_low(unsigned int serial)
00061   {
00062     serial_number_low = serial;
00063     serial_number_low_set = true;
00064 
00065     if (serial_number_high_set) //we received both bytes
00066       compute_serial();
00067   };
00068   void set_serial_number_high(unsigned int serial)
00069   {
00070     serial_number_high = serial;
00071     serial_number_high_set = true;
00072 
00073     if (serial_number_low_set) //we received both bytes
00074       compute_serial();
00075   };
00076   void compute_serial()
00077   {
00078     serial_number = serial_number_low + (serial_number_high * 65536);
00079   };
00080 
00081   double position_unfiltered_;
00082 
00083   uint64_t can_msgs_received_;
00084   uint64_t can_msgs_transmitted_;
00085 
00086   unsigned int pic_firmware_svn_revision_;
00087   unsigned int server_firmware_svn_revision_;
00088   bool firmware_modified_;
00089 
00090   bool serial_number_low_set;
00091   bool serial_number_high_set;
00092   unsigned int serial_number_low;
00093   unsigned int serial_number_high;
00094   unsigned int serial_number;
00095 
00096   unsigned int assembly_data_year;
00097   unsigned int assembly_data_month;
00098   unsigned int assembly_data_day;
00099 
00100   int tests_;
00101   unsigned int can_error_counters;
00102 
00103   std::vector<int> raw_sensor_values_;
00104   std::vector<double> calibrated_sensor_values_;
00105 
00113   std::vector<std::pair<std::string, bool> > flags_;
00114 
00115   std::vector<tactiles::AllTactileData>* tactiles_;
00116 }; //end class SrActuatorState
00117 
00118 class SrMotorActuatorState : public SrActuatorState
00119 {
00120 public:
00121   SrMotorActuatorState() :
00122     strain_gauge_left_(0),
00123     strain_gauge_right_(0),
00124     force_unfiltered_(0.0),
00125     pwm_(0),
00126     motor_gear_ratio(0),
00127     force_control_f_(0),
00128     force_control_p_(0),
00129     force_control_i_(0),
00130     force_control_d_(0),
00131     force_control_imax_(0),
00132     force_control_deadband_(0),
00133     force_control_sign_(0),
00134     force_control_frequency_(0),
00135     temperature_(0.0)
00136   {
00137   }
00138 
00139   signed short strain_gauge_left_;
00140   signed short strain_gauge_right_;
00141 
00142   double force_unfiltered_;
00143 
00144   int pwm_;
00145 
00146   unsigned int motor_gear_ratio;
00147 
00148   int force_control_f_;
00149   int force_control_p_;
00150   int force_control_i_;
00151   int force_control_d_;
00152   int force_control_imax_;
00153   int force_control_deadband_;
00154   int force_control_sign_;
00155   int force_control_frequency_;
00156 
00157   int force_control_pterm;
00158   int force_control_iterm;
00159   int force_control_dterm;
00160   double temperature_;
00161 }; //end class SrMotorActuatorState
00162 
00163 class SrMuscleActuatorState : public SrActuatorState
00164 {
00165 public:
00166   SrMuscleActuatorState() :
00167     pressure_(),
00168     last_commanded_valve_()
00169   {
00170   }
00171 
00173   uint16_t pressure_[2];
00174   int8_t last_commanded_valve_[2];
00175 }; //end class SrMuscleActuatorState
00176 
00177 class SrMuscleActuatorCommand
00178 {
00179 public:
00180   SrMuscleActuatorCommand() :
00181     valve_()
00182   {
00183   }
00184 
00185   int8_t valve_[2];
00186 }; //end class SrMuscleActuatorCommand
00187 
00191 class SrMotorActuator : public ros_ethercat_model::Actuator
00192 {
00193 public:
00194 
00195   SrMotorActuatorState motor_state_;
00196 }; //end class SrMotorActuator
00197 
00201 class SrMuscleActuator : public ros_ethercat_model::Actuator
00202 {
00203 public:
00204 
00205   SrMuscleActuatorState muscle_state_;
00206   SrMuscleActuatorCommand muscle_command_;
00207 }; //end class SrMotorActuator
00208 }
00209 
00210 /* For the emacs weenies in the crowd.
00211 Local Variables:
00212    c-basic-offset: 2
00213 End:
00214  */
00215 
00216 #endif
00217 


sr_hardware_interface
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:25:28