#include <spi_passthrough_controller.hpp>
Public Member Functions | |
bool | command_srv_cb (sr_ronex_msgs::SPI::Request &req, sr_ronex_msgs::SPI::Response &res, size_t spi_out_index) |
void | dynamic_reconfigure_cb (sr_ronex_drivers::SPIConfig &config, uint32_t level) |
virtual bool | init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n) |
Private Member Functions | |
void | post_init_ () |
Private Attributes | |
std::vector< ros::ServiceServer > | command_srv_ |
boost::scoped_ptr < dynamic_reconfigure::Server < sr_ronex_drivers::SPIConfig > > | dynamic_reconfigure_server_ |
Dynamic reconfigure server for setting the parameters of the driver. | |
dynamic_reconfigure::Server < sr_ronex_drivers::SPIConfig > ::CallbackType | function_cb_ |
std::vector< SplittedSPICommand > | standard_commands_ |
Definition at line 41 of file spi_passthrough_controller.hpp.
bool ronex::SPIPassthroughController::command_srv_cb | ( | sr_ronex_msgs::SPI::Request & | req, |
sr_ronex_msgs::SPI::Response & | res, | ||
size_t | spi_out_index | ||
) |
Definition at line 57 of file spi_passthrough_controller.cpp.
void ronex::SPIPassthroughController::dynamic_reconfigure_cb | ( | sr_ronex_drivers::SPIConfig & | config, |
uint32_t | level | ||
) |
Definition at line 123 of file spi_passthrough_controller.cpp.
bool ronex::SPIPassthroughController::init | ( | ros_ethercat_model::RobotStateInterface * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from ronex::SPIBaseController.
Definition at line 32 of file spi_passthrough_controller.cpp.
void ronex::SPIPassthroughController::post_init_ | ( | ) | [private] |
std::vector<ros::ServiceServer> ronex::SPIPassthroughController::command_srv_ [private] |
Definition at line 54 of file spi_passthrough_controller.hpp.
boost::scoped_ptr<dynamic_reconfigure::Server<sr_ronex_drivers::SPIConfig> > ronex::SPIPassthroughController::dynamic_reconfigure_server_ [private] |
Dynamic reconfigure server for setting the parameters of the driver.
Definition at line 62 of file spi_passthrough_controller.hpp.
dynamic_reconfigure::Server<sr_ronex_drivers::SPIConfig>::CallbackType ronex::SPIPassthroughController::function_cb_ [private] |
Definition at line 63 of file spi_passthrough_controller.hpp.
std::vector<SplittedSPICommand> ronex::SPIPassthroughController::standard_commands_ [private] |
Definition at line 59 of file spi_passthrough_controller.hpp.