hwi_switch_robot_hw_sim.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef _COB_GAZEBO_ROS_CONTROL___HWI_SWITCH_ROBOT_HW_SIM_H_
19 #define _COB_GAZEBO_ROS_CONTROL___HWI_SWITCH_ROBOT_HW_SIM_H_
20 
21 
22 // cob_gazebo_ros_control
24 
25 
26 namespace cob_gazebo_ros_control
27 {
28 
30 {
31 public:
32 
33  virtual bool initSim(
34  const std::string& robot_namespace,
35  ros::NodeHandle model_nh,
36  gazebo::physics::ModelPtr parent_model,
37  const urdf::Model *const urdf_model,
38  std::vector<transmission_interface::TransmissionInfo> transmissions);
39 
40  virtual bool enableJointFiltering(ros::NodeHandle nh, std::string filter_joints_param);
41 
42  virtual bool canSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list) const;
43  virtual void doSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list);
44 
45  virtual void stateValid(const bool active);
46 
47 protected:
48 
50  std::set< std::string > enabled_joints_;
51 
52  std::map< std::string, std::set<std::string> > map_hwinterface_to_joints_;
53  std::map< std::string, ControlMethod > map_hwinterface_to_controlmethod_;
54 
56 };
57 
59 
60 }
61 
62 #endif // #ifndef _COB_GAZEBO_ROS_CONTROL___HWI_SWITCH_ROBOT_HW_SIM_H_
virtual bool enableJointFiltering(ros::NodeHandle nh, std::string filter_joints_param)
std::map< std::string, ControlMethod > map_hwinterface_to_controlmethod_
virtual bool canSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const
virtual bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
boost::shared_ptr< HWISwitchRobotHWSim > HWISwitchRobotHWSimPtr
std::map< std::string, std::set< std::string > > map_hwinterface_to_joints_


cob_gazebo_ros_control
Author(s): Felix Messmer
autogenerated on Mon Sep 28 2020 03:19:19