#include <channel.h>
Public Member Functions | |
Channel (int channel_num, std::string ns, Controller *controller) | |
void | feedbackCallback (std::vector< std::string >) |
Protected Member Functions | |
void | cmdCallback (const roboteq_msgs::Command &) |
void | timerCallback (const ros::TimerEvent &) |
Protected Attributes | |
int | channel_num_ |
boost::shared_ptr< Controller > | controller_ |
ros::Time | last_feedback_time_ |
float | max_rpm_ |
ros::NodeHandle | nh_ |
ros::Publisher | pub_feedback_ |
ros::Subscriber | sub_cmd_ |
ros::Timer | timer_init_ |
roboteq::Channel::Channel | ( | int | channel_num, |
std::string | ns, | ||
Controller * | controller | ||
) |
Definition at line 39 of file channel.cpp.
void roboteq::Channel::cmdCallback | ( | const roboteq_msgs::Command & | command | ) | [protected] |
Definition at line 48 of file channel.cpp.
void roboteq::Channel::feedbackCallback | ( | std::vector< std::string > | fields | ) |
Definition at line 61 of file channel.cpp.
void roboteq::Channel::timerCallback | ( | const ros::TimerEvent & | ) | [protected] |
Definition at line 82 of file channel.cpp.
int roboteq::Channel::channel_num_ [protected] |
boost::shared_ptr<Controller> roboteq::Channel::controller_ [protected] |
ros::Time roboteq::Channel::last_feedback_time_ [protected] |
float roboteq::Channel::max_rpm_ [protected] |
ros::NodeHandle roboteq::Channel::nh_ [protected] |
ros::Publisher roboteq::Channel::pub_feedback_ [protected] |
ros::Subscriber roboteq::Channel::sub_cmd_ [protected] |
ros::Timer roboteq::Channel::timer_init_ [protected] |