#include <FmkRobotROSBridge.h>
Public Member Functions | |
| FmkRobotROSBridge (RTC::Manager *manager) | |
| virtual RTC::ReturnCode_t | onExecute (RTC::UniqueId ec_id) |
| bool | onHaltMotorService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| virtual RTC::ReturnCode_t | onInitialize () |
| bool | onResetMotorService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| void | onVelocityCommand (const geometry_msgs::TwistConstPtr &msg) |
| ~FmkRobotROSBridge () | |
Protected Attributes | |
| RTC::CorbaConsumer < VehicleService > | m_service0 |
| RTC::CorbaPort | m_VehicleServicePort |
Private Attributes | |
| ros::ServiceServer | halt_srv |
| double | max_aw |
| double | max_ax |
| double | max_vw |
| double | max_vx |
| ros::NodeHandle | nh |
| ros::Publisher | odometry_pub |
| Position | pos_prev |
| ros::ServiceServer | reset_srv |
| tf::TransformBroadcaster | tf_pub |
| ros::Time | tm_prev |
| geometry_msgs::Twist | velocity |
| ros::Subscriber | velocity_sub |
Definition at line 38 of file FmkRobotROSBridge.h.
| FmkRobotROSBridge::FmkRobotROSBridge | ( | RTC::Manager * | manager | ) |
Definition at line 28 of file FmkRobotROSBridge.cpp.
Definition at line 37 of file FmkRobotROSBridge.cpp.
| RTC::ReturnCode_t FmkRobotROSBridge::onExecute | ( | RTC::UniqueId | ec_id | ) | [virtual] |
Definition at line 118 of file FmkRobotROSBridge.cpp.
| bool FmkRobotROSBridge::onHaltMotorService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) |
Definition at line 290 of file FmkRobotROSBridge.cpp.
| RTC::ReturnCode_t FmkRobotROSBridge::onInitialize | ( | ) | [virtual] |
Definition at line 42 of file FmkRobotROSBridge.cpp.
| bool FmkRobotROSBridge::onResetMotorService | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) |
Definition at line 299 of file FmkRobotROSBridge.cpp.
| void FmkRobotROSBridge::onVelocityCommand | ( | const geometry_msgs::TwistConstPtr & | msg | ) |
Definition at line 262 of file FmkRobotROSBridge.cpp.
Definition at line 134 of file FmkRobotROSBridge.h.
RTC::CorbaConsumer<VehicleService> FmkRobotROSBridge::m_service0 [protected] |
Definition at line 126 of file FmkRobotROSBridge.h.
RTC::CorbaPort FmkRobotROSBridge::m_VehicleServicePort [protected] |
Definition at line 116 of file FmkRobotROSBridge.h.
double FmkRobotROSBridge::max_aw [private] |
Definition at line 137 of file FmkRobotROSBridge.h.
double FmkRobotROSBridge::max_ax [private] |
Definition at line 137 of file FmkRobotROSBridge.h.
double FmkRobotROSBridge::max_vw [private] |
Definition at line 137 of file FmkRobotROSBridge.h.
double FmkRobotROSBridge::max_vx [private] |
Definition at line 137 of file FmkRobotROSBridge.h.
ros::NodeHandle FmkRobotROSBridge::nh [private] |
Definition at line 131 of file FmkRobotROSBridge.h.
Definition at line 133 of file FmkRobotROSBridge.h.
Position FmkRobotROSBridge::pos_prev [private] |
Definition at line 138 of file FmkRobotROSBridge.h.
Definition at line 134 of file FmkRobotROSBridge.h.
Definition at line 135 of file FmkRobotROSBridge.h.
ros::Time FmkRobotROSBridge::tm_prev [private] |
Definition at line 139 of file FmkRobotROSBridge.h.
geometry_msgs::Twist FmkRobotROSBridge::velocity [private] |
Definition at line 136 of file FmkRobotROSBridge.h.
Definition at line 132 of file FmkRobotROSBridge.h.