Public Member Functions | Private Types | Private Attributes | List of all members
scaled_controllers::SpeedScalingStateController Class Reference

#include <speed_scaling_state_controller.h>

Inheritance diagram for scaled_controllers::SpeedScalingStateController:
Inheritance graph
[legend]

Public Member Functions

virtual bool init (scaled_controllers::SpeedScalingInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
 
 SpeedScalingStateController ()=default
 
virtual void starting (const ros::Time &time) override
 
virtual void stopping (const ros::Time &) override
 
virtual void update (const ros::Time &time, const ros::Duration &) override
 
virtual ~SpeedScalingStateController () override=default
 
- Public Member Functions inherited from controller_interface::Controller< scaled_controllers::SpeedScalingInterface >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Private Types

typedef std::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64 > > RtPublisherPtr
 

Private Attributes

std::vector< ros::Timelast_publish_times_
 
double publish_rate_
 
std::vector< RtPublisherPtrrealtime_pubs_
 
std::vector< scaled_controllers::SpeedScalingHandlesensors_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 
- Protected Member Functions inherited from controller_interface::Controller< scaled_controllers::SpeedScalingInterface >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Detailed Description

Definition at line 40 of file speed_scaling_state_controller.h.

Member Typedef Documentation

◆ RtPublisherPtr

Definition at line 55 of file speed_scaling_state_controller.h.

Constructor & Destructor Documentation

◆ SpeedScalingStateController()

scaled_controllers::SpeedScalingStateController::SpeedScalingStateController ( )
default

◆ ~SpeedScalingStateController()

virtual scaled_controllers::SpeedScalingStateController::~SpeedScalingStateController ( )
overridevirtualdefault

Member Function Documentation

◆ init()

bool scaled_controllers::SpeedScalingStateController::init ( scaled_controllers::SpeedScalingInterface hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
overridevirtual

Definition at line 35 of file speed_scaling_state_controller.cpp.

◆ starting()

void scaled_controllers::SpeedScalingStateController::starting ( const ros::Time time)
overridevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 65 of file speed_scaling_state_controller.cpp.

◆ stopping()

void scaled_controllers::SpeedScalingStateController::stopping ( const ros::Time )
overridevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 97 of file speed_scaling_state_controller.cpp.

◆ update()

void scaled_controllers::SpeedScalingStateController::update ( const ros::Time time,
const ros::Duration  
)
overridevirtual

Member Data Documentation

◆ last_publish_times_

std::vector<ros::Time> scaled_controllers::SpeedScalingStateController::last_publish_times_
private

Definition at line 57 of file speed_scaling_state_controller.h.

◆ publish_rate_

double scaled_controllers::SpeedScalingStateController::publish_rate_
private

Definition at line 58 of file speed_scaling_state_controller.h.

◆ realtime_pubs_

std::vector<RtPublisherPtr> scaled_controllers::SpeedScalingStateController::realtime_pubs_
private

Definition at line 56 of file speed_scaling_state_controller.h.

◆ sensors_

std::vector<scaled_controllers::SpeedScalingHandle> scaled_controllers::SpeedScalingStateController::sensors_
private

Definition at line 53 of file speed_scaling_state_controller.h.


The documentation for this class was generated from the following files:


speed_scaling_state_controller
Author(s):
autogenerated on Wed May 18 2022 02:43:20