Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
gpio_controller::Controller Class Reference

#include <gpio_controller.h>

Inheritance diagram for gpio_controller::Controller:
Inheritance graph
[legend]

Public Member Functions

 Controller ()=default
 
bool init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
 
void update (const ros::Time &time, const ros::Duration &period) override
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< rm_control::GpioStateInterface, rm_control::GpioCommandInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
- 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
 
virtual void starting (const ros::Time &)
 
virtual void starting (const ros::Time &)
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::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< rm_msgs::GpioData > > RtpublisherPtr
 

Private Member Functions

void setGpioCmd (const rm_msgs::GpioDataConstPtr &msg)
 

Private Attributes

ros::Subscriber cmd_subscriber_
 
std::vector< rm_control::GpioCommandHandlegpio_command_handles_
 
std::vector< rm_control::GpioStateHandlegpio_state_handles_
 
RtpublisherPtr gpio_state_pub_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< rm_control::GpioStateInterface, rm_control::GpioCommandInterface >
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< rm_control::GpioStateInterface, rm_control::GpioCommandInterface >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< rm_control::GpioStateInterface, rm_control::GpioCommandInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Definition at line 15 of file gpio_controller.h.

Member Typedef Documentation

◆ RtpublisherPtr

typedef std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::GpioData> > gpio_controller::Controller::RtpublisherPtr
private

Definition at line 32 of file gpio_controller.h.

Constructor & Destructor Documentation

◆ Controller()

gpio_controller::Controller::Controller ( )
default

Member Function Documentation

◆ init()

bool gpio_controller::Controller::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
overridevirtual

◆ setGpioCmd()

void gpio_controller::Controller::setGpioCmd ( const rm_msgs::GpioDataConstPtr &  msg)
private

Definition at line 63 of file gpio_controller.cpp.

◆ update()

void gpio_controller::Controller::update ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Implements controller_interface::ControllerBase.

Definition at line 50 of file gpio_controller.cpp.

Member Data Documentation

◆ cmd_subscriber_

ros::Subscriber gpio_controller::Controller::cmd_subscriber_
private

Definition at line 31 of file gpio_controller.h.

◆ gpio_command_handles_

std::vector<rm_control::GpioCommandHandle> gpio_controller::Controller::gpio_command_handles_
private

Definition at line 29 of file gpio_controller.h.

◆ gpio_state_handles_

std::vector<rm_control::GpioStateHandle> gpio_controller::Controller::gpio_state_handles_
private

Definition at line 28 of file gpio_controller.h.

◆ gpio_state_pub_

RtpublisherPtr gpio_controller::Controller::gpio_state_pub_
private

Definition at line 33 of file gpio_controller.h.


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


gpio_controller
Author(s):
autogenerated on Sun May 4 2025 02:57:09