103 ROS_ERROR(
"Cannot initialize this controller because it failed to be constructed");
108 T* hw = robot_hw->
get<T>();
111 ROS_ERROR(
"This controller requires a hardware interface of type '%s'." 112 " Make sure this is registered in the hardware_interface::RobotHW class.",
119 if (!
init(hw, controller_nh) || !
init(hw, root_nh, controller_nh))
121 ROS_ERROR(
"Failed to initialize the controller");
125 claimed_resources.assign(1, iface_res);
136 return hardware_interface::internal::demangledTypeName<T>();
std::string getHardwareInterfaceType() const
Get the name of this controller's hardware interface type.
virtual bool init(T *, ros::NodeHandle &, ros::NodeHandle &)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
bool initRequest(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
Initialize the controller from a RobotHW pointer.
std::vector< hardware_interface::InterfaceResources > ClaimedResources
Abstract Controller Interface.
virtual bool init(T *, ros::NodeHandle &)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
Controller with a specific hardware interface
enum controller_interface::ControllerBase::@0 state_
The current execution state of the controller.