19 #ifndef TELEOP_SUBSCRIBER_HPP
20 #define TELEOP_SUBSCRIBER_HPP
31 #include <geometry_msgs/Twist.h>
32 #include <naoqi_bridge_msgs/JointAnglesWithSpeed.h>
42 TeleopSubscriber(
const std::string&
name,
const std::string& cmd_vel_topic,
const std::string& joint_angles_topic,
const qi::SessionPtr& session );
45 void reset( ros::NodeHandle& nh );
ros::Subscriber sub_cmd_vel_
Definition: teleop.hpp:55
std::string name() const
Definition: subscriber_base.hpp:53
std::string joint_angles_topic_
Definition: teleop.hpp:52
Definition: teleop.hpp:39
Definition: subscriber_base.hpp:39
void joint_angles_callback(const naoqi_bridge_msgs::JointAnglesWithSpeedConstPtr &js_msg)
Definition: teleop.cpp:55
std::string cmd_vel_topic_
Definition: teleop.hpp:51
qi::AnyObject p_motion_
Definition: teleop.hpp:54
ros::Subscriber sub_joint_angles_
Definition: teleop.hpp:56
void cmd_vel_callback(const geometry_msgs::TwistConstPtr &twist_msg)
Definition: teleop.cpp:44
TeleopSubscriber(const std::string &name, const std::string &cmd_vel_topic, const std::string &joint_angles_topic, const qi::SessionPtr &session)
Definition: teleop.cpp:29
void reset(ros::NodeHandle &nh)
Definition: teleop.cpp:36
~TeleopSubscriber()
Definition: teleop.hpp:43