Public Member Functions | Protected Attributes | List of all members
controller::SrTactileSensorController Class Reference

#include <sr_tactile_sensor_controller.hpp>

Inheritance diagram for controller::SrTactileSensorController:
Inheritance graph
[legend]

Public Member Functions

virtual bool init (ros_ethercat_model::RobotStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
 SrTactileSensorController ()
 
virtual void starting (const ros::Time &time)
 
virtual void stopping (const ros::Time &time)
 
virtual void update (const ros::Time &time, const ros::Duration &period)
 
- Public Member Functions inherited from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >
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
 

Protected Attributes

bool initialized_
 
ros::NodeHandle nh_prefix_
 
std::string prefix_
 
double publish_rate_
 
boost::shared_ptr< SrTactileSensorPublishersensor_publisher_
 
std::vector< tactiles::AllTactileData > * sensors_
 

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< ros_ethercat_model::RobotStateInterface >
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 56 of file sr_tactile_sensor_controller.hpp.

Constructor & Destructor Documentation

◆ SrTactileSensorController()

controller::SrTactileSensorController::SrTactileSensorController ( )

Definition at line 51 of file sr_tactile_sensor_controller.cpp.

Member Function Documentation

◆ init()

bool controller::SrTactileSensorController::init ( ros_ethercat_model::RobotStateInterface *  hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
virtual

Definition at line 55 of file sr_tactile_sensor_controller.cpp.

◆ starting()

void controller::SrTactileSensorController::starting ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 167 of file sr_tactile_sensor_controller.cpp.

◆ stopping()

void controller::SrTactileSensorController::stopping ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 171 of file sr_tactile_sensor_controller.cpp.

◆ update()

void controller::SrTactileSensorController::update ( const ros::Time time,
const ros::Duration period 
)
virtual

Member Data Documentation

◆ initialized_

bool controller::SrTactileSensorController::initialized_
protected

Definition at line 72 of file sr_tactile_sensor_controller.hpp.

◆ nh_prefix_

ros::NodeHandle controller::SrTactileSensorController::nh_prefix_
protected

Definition at line 70 of file sr_tactile_sensor_controller.hpp.

◆ prefix_

std::string controller::SrTactileSensorController::prefix_
protected

Definition at line 71 of file sr_tactile_sensor_controller.hpp.

◆ publish_rate_

double controller::SrTactileSensorController::publish_rate_
protected

Definition at line 69 of file sr_tactile_sensor_controller.hpp.

◆ sensor_publisher_

boost::shared_ptr<SrTactileSensorPublisher> controller::SrTactileSensorController::sensor_publisher_
protected

Definition at line 73 of file sr_tactile_sensor_controller.hpp.

◆ sensors_

std::vector<tactiles::AllTactileData>* controller::SrTactileSensorController::sensors_
protected

Definition at line 68 of file sr_tactile_sensor_controller.hpp.


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


sr_tactile_sensor_controller
Author(s): Guillaume Walck
autogenerated on Mon Feb 28 2022 23:51:01