#include <spi_base_controller.hpp>
Public Member Functions | |
virtual bool | init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n) |
SPIBaseController () | |
virtual void | starting (const ros::Time &) |
virtual void | update (const ros::Time &, const ros::Duration &) |
Issues commands to the joint. Should be called at regular intervals. | |
Protected Member Functions | |
void | copy_splitted_to_cmd_ (uint16_t spi_index) |
bool | pre_init_ (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n) |
Protected Attributes | |
uint16_t | cmd_pin_output_states_post_ |
uint16_t | cmd_pin_output_states_pre_ |
std::vector< std::queue < SplittedSPICommand, boost::circular_buffer < SplittedSPICommand > > > | command_queue_ |
std::vector< bool > | delete_status_ |
int | loop_count_ |
ros::NodeHandle | node_ |
ronex::SPI * | spi_ |
std::vector< std::queue < std::pair < SplittedSPICommand, SPIResponse > , boost::circular_buffer < std::pair < SplittedSPICommand, SPIResponse > > > > | status_queue_ |
std::string | topic_prefix_ |
prefix used for creating topics / services |
Definition at line 64 of file spi_base_controller.hpp.
Definition at line 32 of file spi_base_controller.cpp.
void ronex::SPIBaseController::copy_splitted_to_cmd_ | ( | uint16_t | spi_index | ) | [protected] |
Definition at line 173 of file spi_base_controller.cpp.
bool ronex::SPIBaseController::init | ( | ros_ethercat_model::RobotStateInterface * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >.
Reimplemented in ronex::SPIPassthroughController, and ronex::SPISensorReadController.
Definition at line 36 of file spi_base_controller.cpp.
bool ronex::SPIBaseController::pre_init_ | ( | ros_ethercat_model::RobotStateInterface * | robot, |
ros::NodeHandle & | n | ||
) | [protected] |
Definition at line 41 of file spi_base_controller.cpp.
void ronex::SPIBaseController::starting | ( | const ros::Time & | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 110 of file spi_base_controller.cpp.
void ronex::SPIBaseController::update | ( | const ros::Time & | , |
const ros::Duration & | |||
) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Implements controller_interface::ControllerBase.
Reimplemented in ronex::SPISensorReadController.
Definition at line 118 of file spi_base_controller.cpp.
uint16_t ronex::SPIBaseController::cmd_pin_output_states_post_ [protected] |
Definition at line 94 of file spi_base_controller.hpp.
uint16_t ronex::SPIBaseController::cmd_pin_output_states_pre_ [protected] |
Definition at line 93 of file spi_base_controller.hpp.
std::vector<std::queue<SplittedSPICommand, boost::circular_buffer<SplittedSPICommand> > > ronex::SPIBaseController::command_queue_ [protected] |
Definition at line 89 of file spi_base_controller.hpp.
std::vector<bool> ronex::SPIBaseController::delete_status_ [protected] |
Definition at line 102 of file spi_base_controller.hpp.
int ronex::SPIBaseController::loop_count_ [protected] |
Definition at line 85 of file spi_base_controller.hpp.
ros::NodeHandle ronex::SPIBaseController::node_ [protected] |
Definition at line 80 of file spi_base_controller.hpp.
ronex::SPI* ronex::SPIBaseController::spi_ [protected] |
Definition at line 87 of file spi_base_controller.hpp.
std::vector<std::queue<std::pair<SplittedSPICommand, SPIResponse>, boost::circular_buffer<std::pair<SplittedSPICommand, SPIResponse > > > > ronex::SPIBaseController::status_queue_ [protected] |
Definition at line 91 of file spi_base_controller.hpp.
std::string ronex::SPIBaseController::topic_prefix_ [protected] |
prefix used for creating topics / services
Definition at line 83 of file spi_base_controller.hpp.