28 #ifndef COMBINED_ROBOT_HW_COMBINED_ROBOT_HW_H 29 #define COMBINED_ROBOT_HW_COMBINED_ROBOT_HW_H 77 virtual bool prepareSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list,
78 const std::list<hardware_interface::ControllerInfo>& stop_list);
84 virtual void doSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list,
85 const std::list<hardware_interface::ControllerInfo>& stop_list);
115 std::list<hardware_interface::ControllerInfo>& filtered_list,
std::vector< hardware_interface::RobotHWSharedPtr > robot_hw_list_
pluginlib::ClassLoader< hardware_interface::RobotHW > robot_hw_loader_
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
virtual ~CombinedRobotHW()
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
The init function is called to initialize the RobotHW from a non-realtime thread. ...
virtual bool loadRobotHW(const std::string &name)
virtual void read(const ros::Time &time, const ros::Duration &period)
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
ros::NodeHandle robot_hw_nh_
virtual void write(const ros::Time &time, const ros::Duration &period)
void filterControllerList(const std::list< hardware_interface::ControllerInfo > &list, std::list< hardware_interface::ControllerInfo > &filtered_list, hardware_interface::RobotHWSharedPtr robot_hw)
Filters the start and stop lists so that they only contain the controllers and resources that corresp...