00001 00035 #ifndef RIDGEBACK_BASE_RIDGEBACK_HARDWARE_H 00036 #define RIDGEBACK_BASE_RIDGEBACK_HARDWARE_H 00037 00038 #include <vector> 00039 00040 #include "boost/thread.hpp" 00041 #include "boost/foreach.hpp" 00042 #include "boost/shared_ptr.hpp" 00043 #include "hardware_interface/joint_state_interface.h" 00044 #include "hardware_interface/joint_command_interface.h" 00045 #include "hardware_interface/robot_hw.h" 00046 #include "ros/ros.h" 00047 #include "sensor_msgs/JointState.h" 00048 #include "puma_motor_driver/socketcan_gateway.h" 00049 #include "puma_motor_driver/driver.h" 00050 #include "puma_motor_driver/multi_driver_node.h" 00051 #include "puma_motor_msgs/MultiFeedback.h" 00052 00053 namespace ridgeback_base 00054 { 00055 00056 class RidgebackHardware : public hardware_interface::RobotHW 00057 { 00058 public: 00059 RidgebackHardware(ros::NodeHandle& nh, ros::NodeHandle& pnh, 00060 puma_motor_driver::Gateway& gateway); 00061 void init(); // Connect to CAN 00062 bool connectIfNotConnected(); // Keep trying till it connects 00063 std::vector<puma_motor_driver::Driver>& getDrivers(); 00064 void configure(); // Configures the motor drivers 00065 void verify(); 00066 bool isActive(); 00067 00068 void powerHasNotReset(); // Checks if power has been reset 00069 bool inReset(); // Returns if the cm should be reset based on the state of the motors drivers. 00070 // If they have been configured. 00071 void requestData(); 00072 void updateJointsFromHardware(); 00073 void command(); 00074 00075 void canSend(); 00076 void canRead(); 00077 00078 private: 00079 ros::NodeHandle nh_, pnh_; 00080 00081 puma_motor_driver::Gateway& gateway_; 00082 std::vector<puma_motor_driver::Driver> drivers_; 00083 boost::shared_ptr<puma_motor_driver::MultiDriverNode> multi_driver_node_; 00084 00085 bool active_; 00086 double gear_ratio_; 00087 int encoder_cpr_; 00088 00089 // ROS Control interfaces 00090 hardware_interface::JointStateInterface joint_state_interface_; 00091 hardware_interface::VelocityJointInterface velocity_joint_interface_; 00092 00093 // These are mutated on the controls thread only. 00094 struct Joint 00095 { 00096 double position; 00097 double velocity; 00098 double effort; 00099 double velocity_command; 00100 00101 Joint() : position(0), velocity(0), effort(0), velocity_command(0) 00102 { 00103 } 00104 } 00105 joints_[4]; 00106 }; 00107 00108 } // namespace ridgeback_base 00109 00110 #endif // RIDGEBACK_BASE_RIDGEBACK_HARDWARE_H