Go to the documentation of this file.
31 #ifndef MECHANISM_CONTROL_H
32 #define MECHANISM_CONTROL_H
47 #include <pr2_mechanism_msgs/ListControllerTypes.h>
48 #include <pr2_mechanism_msgs/ListControllers.h>
49 #include <pr2_mechanism_msgs/ReloadControllerLibraries.h>
50 #include <pr2_mechanism_msgs/LoadController.h>
51 #include <pr2_mechanism_msgs/UnloadController.h>
52 #include <pr2_mechanism_msgs/SwitchController.h>
53 #include <pr2_mechanism_msgs/MechanismStatistics.h>
54 #include <sensor_msgs/JointState.h>
55 #include <boost/thread/condition.hpp>
71 bool initXml(TiXmlElement* config);
76 const int strictness);
117 pr2_mechanism_msgs::ListControllerTypes::Response &resp);
119 pr2_mechanism_msgs::ListControllers::Response &resp);
121 pr2_mechanism_msgs::SwitchController::Response &resp);
123 pr2_mechanism_msgs::LoadController::Response &resp);
125 pr2_mechanism_msgs::UnloadController::Response &resp);
127 pr2_mechanism_msgs::ReloadControllerLibraries::Response &resp);
virtual ~ControllerManager()
Statistics pre_update_stats_
boost::shared_ptr< pluginlib::ClassLoader< pr2_controller_interface::Controller > > controller_loader_
ros::Time last_published_joint_state_
ros::ServiceServer srv_reload_libraries_
bool unloadControllerSrv(pr2_mechanism_msgs::UnloadController::Request &req, pr2_mechanism_msgs::UnloadController::Response &resp)
pr2_mechanism_model::Robot model_
ros::NodeHandle controller_node_
ros::Time last_published_mechanism_stats_
bool motors_previously_halted_
ros::ServiceServer srv_unload_controller_
bool loadController(const std::string &name)
int current_controllers_list_
bool initXml(TiXmlElement *config)
bool listControllersSrv(pr2_mechanism_msgs::ListControllers::Request &req, pr2_mechanism_msgs::ListControllers::Response &resp)
void getControllerSchedule(std::vector< size_t > &schedule)
ros::Duration publish_period_joint_state_
ControllerManager(pr2_hardware_interface::HardwareInterface *hw, const ros::NodeHandle &nh=ros::NodeHandle())
virtual pr2_controller_interface::Controller * getControllerByName(const std::string &name)
boost::mutex services_lock_
bool reloadControllerLibrariesSrv(pr2_mechanism_msgs::ReloadControllerLibraries::Request &req, pr2_mechanism_msgs::ReloadControllerLibraries::Response &resp)
bool loadControllerSrv(pr2_mechanism_msgs::LoadController::Request &req, pr2_mechanism_msgs::LoadController::Response &resp)
void getControllerNames(std::vector< std::string > &v)
bool unloadController(const std::string &name)
realtime_tools::RealtimePublisher< pr2_mechanism_msgs::MechanismStatistics > pub_mech_stats_
bool switchControllerSrv(pr2_mechanism_msgs::SwitchController::Request &req, pr2_mechanism_msgs::SwitchController::Response &resp)
void publishMechanismStatistics()
ros::ServiceServer srv_list_controller_types_
def start_controllers(names)
Statistics post_update_stats_
bool listControllerTypesSrv(pr2_mechanism_msgs::ListControllerTypes::Request &req, pr2_mechanism_msgs::ListControllerTypes::Response &resp)
std::vector< ControllerSpec > controllers_lists_[2]
ros::ServiceServer srv_list_controllers_
bool switchController(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, const int strictness)
std::vector< size_t > controllers_scheduling_[2]
ros::ServiceServer srv_load_controller_
def stop_controllers(names)
std::vector< pr2_controller_interface::Controller * > stop_request_
pr2_mechanism_model::RobotState * state_
ros::Duration publish_period_mechanism_stats_
realtime_tools::RealtimePublisher< sensor_msgs::JointState > pub_joint_state_
ros::ServiceServer srv_switch_controller_
std::vector< pr2_controller_interface::Controller * > start_request_
boost::mutex controllers_lock_
pr2_controller_manager
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Mon Mar 6 2023 03:49:21