Go to the documentation of this file.00001
00033 #ifndef roch_BASE_roch_HARDWARE_H
00034 #define roch_BASE_roch_HARDWARE_H
00035
00036 #include "roch_base/roch_diagnostics.h"
00037 #include "diagnostic_updater/diagnostic_updater.h"
00038 #include "hardware_interface/joint_state_interface.h"
00039 #include "hardware_interface/joint_command_interface.h"
00040 #include "hardware_interface/imu_sensor_interface.h"
00041 #include "hardware_interface/robot_hw.h"
00042 #include "ros/ros.h"
00043 #include "sensor_msgs/JointState.h"
00044 #include "roch_msgs/RochStatus.h"
00045 #include "roch_msgs/CliffEvent.h"
00046 #include "roch_msgs/UltEvent.h"
00047 #include "roch_msgs/PSDEvent.h"
00048 #include "roch_msgs/SensorState.h"
00049 #include <sensor_msgs/Imu.h>
00050 #include <tf/tf.h>
00051 #include <string>
00052
00053 #include <angles/angles.h>
00054 #include <std_msgs/String.h>
00055 #include "roch_base/core/Message.h"
00056 #include "roch_base/core/serial.h"
00057 namespace roch_base
00058 {
00059
00063 class rochHardware :
00064 public hardware_interface::RobotHW
00065 {
00066
00067 public:
00068 rochHardware(ros::NodeHandle nh, ros::NodeHandle private_nh, double target_control_freq);
00069
00070 void updateJointsFromHardware();
00071
00072 void writeCommandsToHardware();
00073
00074 void updateDiagnostics();
00075
00076 void reportLoopDuration(const ros::Duration &duration);
00077
00078 void writeOverallSpeedCommandsToHardware();
00079
00080 void getRangefinderData();
00081
00082 void getPlatformName();
00083
00084 void getPlatAccData();
00085
00086 void getDifferentControlConstantData();
00087
00088 void showRawData();
00089
00090 void publishRawData();
00091
00092 public:
00093
00094 hardware_interface::ImuSensorHandle::Data imuMsgData;
00095 double orientation[4];
00096 double orientation_covariance [9];
00097 double angular_velocity_covariance[9] ;
00098 double linear_acceleration_covariance[9] ;
00099 double angular_velocity[3] ;
00100 double linear_acceleration[3];
00101 private:
00102
00103 void initializeDiagnostics();
00104
00105 void resetTravelOffset();
00106
00107 void registerControlInterfaces();
00108
00109 double linearToAngular(const double &travel) const;
00110
00111 double angularToLinear(const double &angle) const;
00112
00113 void limitDifferentialSpeed(double &travel_speed_left, double &travel_speed_right);
00114
00115 void publishCliffEvent(const double &left, const double &right);
00116
00117 void publishUltEvent(const double &left, const double ¢er, const double &right);
00118
00119 void publishPSDEvent(const double &left, const double ¢er, const double &right);
00120
00121 void publishWheelEvent(const float &leftOffset, const float &rightOffset);
00122
00123 void publishSensorState();
00124
00125 ros::NodeHandle nh_, private_nh_;
00126
00127
00128 hardware_interface::JointStateInterface joint_state_interface_;
00129 hardware_interface::VelocityJointInterface velocity_joint_interface_;
00130 hardware_interface::ImuSensorInterface imu_sensor_interface_;
00131
00132
00133 ros::Publisher diagnostic_publisher_;
00134 ros::Publisher raw_data_command_publisher_;
00135 ros::Publisher cliff_event_publisher_,ult_event_publisher_,psd_event_publisher_;
00136 ros::Publisher sensor_state_publisher_;
00137 roch_msgs::RochStatus roch_status_msg_;
00138 diagnostic_updater::Updater diagnostic_updater_;
00139 rochHardwareDiagnosticTask<sawyer::DataSystemStatus> system_status_task_;
00140 rochHardwareDiagnosticTask<sawyer::DataPowerSystem> power_status_task_;
00141 rochHardwareDiagnosticTask<sawyer::DataSafetySystemStatus> safety_status_task_;
00142 rochSoftwareDiagnosticTask software_status_task_;
00143
00144
00145 double wheel_diameter_, max_accel_, max_speed_;
00146
00147 double polling_timeout_;
00148
00149 double cliff_height_;
00150
00151
00152 double ult_length_;
00153
00154 double PSD_length_;
00155 std::string gyro_link_frame_;
00156 std::vector<double> cliffbottom;
00157 std::vector<double> ultbottom;
00158 std::vector<double> psdbottom;
00162 struct Joint
00163 {
00164 double position;
00165 double position_offset;
00166 double velocity;
00167 double effort;
00168 double velocity_command;
00169
00170 Joint() :
00171 position(0), velocity(0), effort(0), velocity_command(0)
00172 { }
00173 } joints_[2];
00174
00175 struct ThreeAxisGyro{
00176 double X;
00177 double X_Offset;
00178 double Y;
00179 double Y_Offset;
00180 double Z;
00181 double Z_Offset;
00182
00183 ThreeAxisGyro() :
00184 X(0), X_Offset(0), Y(0), Y_Offset(0), Z(0), Z_Offset(0)
00185 { }
00186 }gyroData;
00187
00188 struct SixAxisGyro{
00189 double angle;
00190 double angle_rate;
00191 double angle_rate_offset;
00192 double angle_offset;
00193 ThreeAxisGyro acc;
00194
00195 SixAxisGyro() :
00196 angle(0), angle_rate(0), angle_rate_offset(0), angle_offset(0)
00197 { }
00198 }sixGyro;
00199
00200 struct CliffEvent{
00201 enum State {
00202 Floor,
00203 Cliff
00204 } state;
00205 enum Sensor {
00206 Left,
00207 Right
00208 } sensor;
00209 double leftbottom;
00210 double rightbottom;
00211 };
00212
00213 struct UltEvent{
00214 enum State {
00215 Normal,
00216 Near
00217 } state;
00218 enum Sensor {
00219 Left,
00220 Center,
00221 Right
00222 } sensor;
00223 double leftbottom;
00224 double centerbottom;
00225 double rightbottom;
00226 };
00227
00228 struct PSDEvent{
00229 enum State {
00230 Normal,
00231 Near
00232 } state;
00233 enum Sensor {
00234 Left,
00235 Center,
00236 Right
00237 } sensor;
00238 double leftbottom;
00239 double centerbottom;
00240 double rightbottom;
00241 };
00242
00243 CliffEvent leftcliffevent,rightcliffevent;
00244
00245 UltEvent leftultevent, centerultevent, rightultevent;
00246
00247 PSDEvent leftpsdevent, centerpsdevent, rightpsdevent;
00248 };
00249
00250 };
00251
00252
00253 #endif // ROCH_BASE_ROCH_HARDWARE_H