#include <teleop.hpp>

Public Member Functions | |
| void | cmd_vel_callback (const geometry_msgs::TwistConstPtr &twist_msg) |
| void | joint_angles_callback (const naoqi_bridge_msgs::JointAnglesWithSpeedConstPtr &js_msg) |
| void | reset (ros::NodeHandle &nh) |
| TeleopSubscriber (const std::string &name, const std::string &cmd_vel_topic, const std::string &joint_angles_topic, const qi::SessionPtr &session) | |
| ~TeleopSubscriber () | |
Public Member Functions inherited from naoqi::subscriber::BaseSubscriber< TeleopSubscriber > | |
| BaseSubscriber (const std::string &name, const std::string &topic, qi::SessionPtr session) | |
| bool | isInitialized () const |
| std::string | name () const |
| std::string | topic () const |
| virtual | ~BaseSubscriber () |
Private Attributes | |
| std::string | cmd_vel_topic_ |
| std::string | joint_angles_topic_ |
| qi::AnyObject | p_motion_ |
| ros::Subscriber | sub_cmd_vel_ |
| ros::Subscriber | sub_joint_angles_ |
Additional Inherited Members | |
Protected Attributes inherited from naoqi::subscriber::BaseSubscriber< TeleopSubscriber > | |
| bool | is_initialized_ |
| std::string | name_ |
| const robot::Robot & | robot_ |
| qi::SessionPtr | session_ |
| std::string | topic_ |
Definition at line 39 of file teleop.hpp.
| naoqi::subscriber::TeleopSubscriber::TeleopSubscriber | ( | const std::string & | name, |
| const std::string & | cmd_vel_topic, | ||
| const std::string & | joint_angles_topic, | ||
| const qi::SessionPtr & | session | ||
| ) |
Definition at line 29 of file teleop.cpp.
|
inline |
Definition at line 43 of file teleop.hpp.
| void naoqi::subscriber::TeleopSubscriber::cmd_vel_callback | ( | const geometry_msgs::TwistConstPtr & | twist_msg | ) |
Definition at line 44 of file teleop.cpp.
| void naoqi::subscriber::TeleopSubscriber::joint_angles_callback | ( | const naoqi_bridge_msgs::JointAnglesWithSpeedConstPtr & | js_msg | ) |
Definition at line 55 of file teleop.cpp.
| void naoqi::subscriber::TeleopSubscriber::reset | ( | ros::NodeHandle & | nh | ) |
Definition at line 36 of file teleop.cpp.
|
private |
Definition at line 51 of file teleop.hpp.
|
private |
Definition at line 52 of file teleop.hpp.
|
private |
Definition at line 54 of file teleop.hpp.
|
private |
Definition at line 55 of file teleop.hpp.
|
private |
Definition at line 56 of file teleop.hpp.