Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef _COB_GAZEBO_ROS_CONTROL___HWI_SWITCH_ROBOT_HW_SIM_H_
00019 #define _COB_GAZEBO_ROS_CONTROL___HWI_SWITCH_ROBOT_HW_SIM_H_
00020
00021
00022
00023 #include <gazebo_ros_control/default_robot_hw_sim.h>
00024
00025
00026 namespace cob_gazebo_ros_control
00027 {
00028
00029 class HWISwitchRobotHWSim : public gazebo_ros_control::DefaultRobotHWSim
00030 {
00031 public:
00032
00033 virtual bool initSim(
00034 const std::string& robot_namespace,
00035 ros::NodeHandle model_nh,
00036 gazebo::physics::ModelPtr parent_model,
00037 const urdf::Model *const urdf_model,
00038 std::vector<transmission_interface::TransmissionInfo> transmissions);
00039
00040 virtual bool enableJointFiltering(ros::NodeHandle nh, std::string filter_joints_param);
00041
00042 virtual bool canSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list) const;
00043 virtual void doSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list);
00044
00045 virtual void stateValid(const bool active);
00046
00047 protected:
00048
00049 bool enable_joint_filtering_;
00050 std::set< std::string > enabled_joints_;
00051
00052 std::set< std::string > position_joints_;
00053 std::map< std::string, std::set<std::string> > map_hwinterface_to_joints_;
00054 std::map< std::string, ControlMethod > map_hwinterface_to_controlmethod_;
00055
00056 bool state_valid_;
00057 };
00058
00059 typedef boost::shared_ptr<HWISwitchRobotHWSim> HWISwitchRobotHWSimPtr;
00060
00061 }
00062
00063 #endif // #ifndef _COB_GAZEBO_ROS_CONTROL___HWI_SWITCH_ROBOT_HW_SIM_H_