61 RobotHW::registerInterface<typename T::parent_type>(interface);
67 available_interfaces_[T::INTERFACE_NAME] = interface;
77 double max_vel_change, std::string wrench_frame);
82 void doSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list,
83 const std::list<hardware_interface::ControllerInfo>& stop_list);
ROSController(URCommander &commander, TrajectoryFollower &follower, std::vector< std::string > &joint_names, double max_vel_change, std::string wrench_frame)
virtual bool consume(RTState_V3_2__3 &state)
virtual bool consume(RTState_V1_8 &state)
void registerInterface(T *interface)
VelocityInterface velocity_interface_
virtual bool consume(RTState_V3_0__1 &state)
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
HardwareInterface * active_interface_
JointInterface joint_interface_
virtual void onRobotStateChange(RobotState state)
PositionInterface position_interface_
controller_manager::ControllerManager controller_
bool robot_state_received_
void registerControllereInterface(T *interface)
std::atomic< bool > service_enabled_
virtual void setupConsumer()
WrenchInterface wrench_interface_
std::map< std::string, HardwareInterface * > available_interfaces_
virtual bool consume(RTState_V1_6__7 &state)
std::atomic< uint32_t > service_cooldown_
void read(RTShared &state)