Go to the documentation of this file.00001
00025 #ifndef __SR_GAZEBO_SIM_GAZEBO_HARDWARE_SIM_H
00026 #define __SR_GAZEBO_SIM_GAZEBO_HARDWARE_SIM_H
00027
00028 #include <string>
00029 #include <vector>
00030 #include <boost/unordered_map.hpp>
00031 #include <ros/ros.h>
00032 #include <pluginlib/class_list_macros.h>
00033 #include "ros_ethercat_model/robot_state.hpp"
00034 #include <gazebo_ros_control/default_robot_hw_sim.h>
00035 #include <gazebo_ros_control/robot_hw_sim.h>
00036 #include <urdf/model.h>
00037
00038 namespace sr_gazebo_sim
00039 {
00040
00041 class SrGazeboHWSim : public gazebo_ros_control::DefaultRobotHWSim
00042 {
00043 public:
00044 SrGazeboHWSim();
00045
00046 bool initSim(
00047 const std::string &robot_namespace,
00048 ros::NodeHandle model_nh,
00049 gazebo::physics::ModelPtr parent_model,
00050 const urdf::Model *const urdf_model,
00051 std::vector <transmission_interface::TransmissionInfo> transmissions);
00052
00053 void readSim(ros::Time time, ros::Duration period);
00054
00055 void writeSim(ros::Time time, ros::Duration period);
00056
00057 protected:
00058 template <class T>
00059 void fixJointName(std::vector<T> *items, const std::string old_joint_name, const std::string new_joint_name) const;
00060
00061 void addFakeTransmissionsForJ0(std::vector<transmission_interface::TransmissionInfo> *transmissions);
00062
00063 void initializeFakeRobotState(const urdf::Model*const urdf_model,
00064 const std::vector<transmission_interface::TransmissionInfo> &transmissions);
00065
00066 bool isHandJoint(const std::vector<transmission_interface::TransmissionInfo> &transmissions,
00067 const std::string &joint_name) const;
00068
00069 void registerSecondHardwareInterface(std::vector<transmission_interface::TransmissionInfo> transmissions);
00070
00071 static const std::string j0_transmission_name;
00072 static const std::string simple_transmission_name;
00073
00074 ros_ethercat_model::RobotState fake_state_;
00075 boost::unordered_map<std::string, std::string> j2_j1_joints_;
00076 };
00077
00078 typedef boost::shared_ptr <SrGazeboHWSim> SrGazeboHWSimPtr;
00079
00080 }
00081
00082
00083 #endif // __SR_GAZEBO_SIM_GAZEBO_HARDWARE_SIM_H