28 #ifndef UR_CONTROLLERS_SPEED_SCALING_STATE_CONTROLLER_H_INCLUDED 29 #define UR_CONTROLLERS_SPEED_SCALING_STATE_CONTROLLER_H_INCLUDED 33 #include <std_msgs/Float64.h> 53 typedef std::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64> >
RtPublisherPtr;
59 #endif // ifndef UR_CONTROLLERS_SPEED_SCALING_STATE_CONTROLLER_H_INCLUDED
virtual void update(const ros::Time &time, const ros::Duration &) override
virtual void stopping(const ros::Time &) override
virtual bool init(SpeedScalingInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
std::vector< ros::Time > last_publish_times_
SpeedScalingStateController()=default
virtual ~SpeedScalingStateController() override=default
virtual void starting(const ros::Time &time) override
std::vector< RtPublisherPtr > realtime_pubs_
std::vector< SpeedScalingHandle > sensors_
std::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64 > > RtPublisherPtr
Hardware interface to support reading the speed scaling factor.