Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
nao_teleop::TeleopNaoJoy Class Reference

Nao Teleoperation via Joystick. Ct. More...

#include <teleop_nao_joy.h>

List of all members.

Public Member Functions

bool callBodyPoseClient (const std::string &poseName)
 calls m_bodyPoseClient on the poseName, to execute a body pose
void pubMsg ()
 Publish motion message to Nao.
ros::Subscriber subscribeToJoystick ()
 Subscribe to joystick using default hander (TeleopNaoJoy::joyCallback).
 TeleopNaoJoy ()

Public Attributes

ros::NodeHandle nh
ros::NodeHandle privateNh

Protected Member Functions

bool axisValid (int axis, const sensor_msgs::Joy::ConstPtr &joy) const
 Check whether an axis id is valid.
bool buttonChanged (int button, const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::Joy::ConstPtr &prevJoy) const
 Returns true when a button has changed compared to previous joystick state.
bool buttonPressed (int button, const sensor_msgs::Joy::ConstPtr &joy) const
 Returns true when a valid button is pressed.
bool buttonTriggered (int button, const sensor_msgs::Joy::ConstPtr &joy) const
 Returns true when a valid button is triggered.
bool inhibitWalk (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
 Inhibit joystick from sending walk commands.
void initializePreviousJoystick (const sensor_msgs::Joy::ConstPtr &joy)
void joyCallback (const sensor_msgs::Joy::ConstPtr &joy)
 Callback for joystick messages.
void setPreviousJoystick (const sensor_msgs::Joy::ConstPtr &joy)
template<class M , class T >
ros::Subscriber subscribeToJoystick (void(T::*fp)(M), T *obj)
 Subscribe to joystick using this callback function.
bool uninhibitWalk (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
 Uninhibit joystick from sending walk commands.

Protected Attributes

actionlib::SimpleActionClient
< naoqi_bridge_msgs::BodyPoseAction > 
m_bodyPoseClient
ros::Duration m_bodyPoseTimeOut
ros::ServiceClient m_cmdVelClient
int m_crouchBtn
int m_enableBtn
bool m_enabled
naoqi_bridge_msgs::JointAnglesWithSpeed m_headAngles
int m_headPitchAxis
ros::Publisher m_headPub
int m_headYawAxis
int m_inhibitCounter
ros::ServiceServer m_inhibitWalkSrv
int m_initPoseBtn
ros::Subscriber m_joySub
double m_maxHeadPitch
double m_maxHeadYaw
double m_maxVw
double m_maxVx
double m_maxVy
int m_modifyHeadBtn
geometry_msgs::Twist m_motion
ros::Publisher m_moveBtnPub
ros::Publisher m_movePub
bool m_prevHeadZero
sensor_msgs::Joy::ConstPtr m_previousJoystick
bool m_previousJoystick_initialized
bool m_prevMotionZero
ros::Publisher m_speechPub
ros::ServiceClient m_stiffnessDisableClient
ros::ServiceClient m_stiffnessEnableClient
int m_turnAxis
ros::ServiceServer m_uninhibitWalkSrv
int m_xAxis
int m_yAxis

Detailed Description

Nao Teleoperation via Joystick. Ct.

Subscribes to "joy" messages, and remaps them to Nao teleoperation commands.

Definition at line 53 of file teleop_nao_joy.h.


Constructor & Destructor Documentation

Definition at line 40 of file teleop_nao_joy.cpp.


Member Function Documentation

bool nao_teleop::TeleopNaoJoy::axisValid ( int  axis,
const sensor_msgs::Joy::ConstPtr &  joy 
) const [protected]

Check whether an axis id is valid.

Parameters:
axis
joy
Returns:

Definition at line 259 of file teleop_nao_joy.cpp.

bool nao_teleop::TeleopNaoJoy::buttonChanged ( int  button,
const sensor_msgs::Joy::ConstPtr &  joy,
const sensor_msgs::Joy::ConstPtr &  prevJoy 
) const [protected]

Returns true when a button has changed compared to previous joystick state.

Parameters:
button
joy
prevJoy
Returns:

Definition at line 248 of file teleop_nao_joy.cpp.

bool nao_teleop::TeleopNaoJoy::buttonPressed ( int  button,
const sensor_msgs::Joy::ConstPtr &  joy 
) const [protected]

Returns true when a valid button is pressed.

Parameters:
button
joy
Returns:

Definition at line 222 of file teleop_nao_joy.cpp.

bool nao_teleop::TeleopNaoJoy::buttonTriggered ( int  button,
const sensor_msgs::Joy::ConstPtr &  joy 
) const [protected]

Returns true when a valid button is triggered.

Parameters:
button
joy
Returns:

Definition at line 233 of file teleop_nao_joy.cpp.

bool nao_teleop::TeleopNaoJoy::callBodyPoseClient ( const std::string &  poseName)

calls m_bodyPoseClient on the poseName, to execute a body pose

Returns:
success of actionlib call

Definition at line 98 of file teleop_nao_joy.cpp.

bool nao_teleop::TeleopNaoJoy::inhibitWalk ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
) [protected]

Inhibit joystick from sending walk commands.

The teleop_nao node sends walk commands to the robot continuously, even when the joystick is in its zero position. This can disturb motions initiated by other nodes. To stop the teleop_nao node from publishing walk commands, call this service before you execute your own motion commands.

Call the /uninhibit_walk service to enable sending walk commands again.

Definition at line 303 of file teleop_nao_joy.cpp.

void nao_teleop::TeleopNaoJoy::initializePreviousJoystick ( const sensor_msgs::Joy::ConstPtr &  joy) [protected]

Definition at line 118 of file teleop_nao_joy.cpp.

void nao_teleop::TeleopNaoJoy::joyCallback ( const sensor_msgs::Joy::ConstPtr &  joy) [protected]

Callback for joystick messages.

Parameters:
joy

Definition at line 138 of file teleop_nao_joy.cpp.

Publish motion message to Nao.

Definition at line 266 of file teleop_nao_joy.cpp.

void nao_teleop::TeleopNaoJoy::setPreviousJoystick ( const sensor_msgs::Joy::ConstPtr &  joy) [inline, protected]

Definition at line 79 of file teleop_nao_joy.h.

Subscribe to joystick using default hander (TeleopNaoJoy::joyCallback).

Definition at line 94 of file teleop_nao_joy.cpp.

template<class M , class T >
ros::Subscriber nao_teleop::TeleopNaoJoy::subscribeToJoystick ( void(T::*)(M)  fp,
T obj 
) [inline, protected]

Subscribe to joystick using this callback function.

Definition at line 92 of file teleop_nao_joy.h.

bool nao_teleop::TeleopNaoJoy::uninhibitWalk ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
) [protected]

Uninhibit joystick from sending walk commands.

Call the /uninhibit_walk service to enable sending walk commands again.

If /inhibit_walk was called more than once, the walk commands will only be enabled after /uninhibit_walk was called for the same number of times.

Definition at line 331 of file teleop_nao_joy.cpp.


Member Data Documentation

actionlib::SimpleActionClient<naoqi_bridge_msgs::BodyPoseAction> nao_teleop::TeleopNaoJoy::m_bodyPoseClient [protected]

Definition at line 133 of file teleop_nao_joy.h.

Definition at line 117 of file teleop_nao_joy.h.

Definition at line 130 of file teleop_nao_joy.h.

Definition at line 106 of file teleop_nao_joy.h.

Definition at line 108 of file teleop_nao_joy.h.

Definition at line 83 of file teleop_nao_joy.h.

naoqi_bridge_msgs::JointAnglesWithSpeed nao_teleop::TeleopNaoJoy::m_headAngles [protected]

Definition at line 135 of file teleop_nao_joy.h.

Definition at line 105 of file teleop_nao_joy.h.

Definition at line 125 of file teleop_nao_joy.h.

Definition at line 104 of file teleop_nao_joy.h.

Definition at line 118 of file teleop_nao_joy.h.

Definition at line 128 of file teleop_nao_joy.h.

Definition at line 107 of file teleop_nao_joy.h.

Definition at line 126 of file teleop_nao_joy.h.

Definition at line 114 of file teleop_nao_joy.h.

Definition at line 113 of file teleop_nao_joy.h.

Definition at line 112 of file teleop_nao_joy.h.

Definition at line 110 of file teleop_nao_joy.h.

Definition at line 111 of file teleop_nao_joy.h.

Definition at line 109 of file teleop_nao_joy.h.

geometry_msgs::Twist nao_teleop::TeleopNaoJoy::m_motion [protected]

Definition at line 134 of file teleop_nao_joy.h.

Definition at line 124 of file teleop_nao_joy.h.

Definition at line 123 of file teleop_nao_joy.h.

Definition at line 116 of file teleop_nao_joy.h.

sensor_msgs::Joy::ConstPtr nao_teleop::TeleopNaoJoy::m_previousJoystick [protected]

Definition at line 121 of file teleop_nao_joy.h.

Definition at line 120 of file teleop_nao_joy.h.

Definition at line 115 of file teleop_nao_joy.h.

Definition at line 127 of file teleop_nao_joy.h.

Definition at line 131 of file teleop_nao_joy.h.

Definition at line 132 of file teleop_nao_joy.h.

Definition at line 103 of file teleop_nao_joy.h.

Definition at line 129 of file teleop_nao_joy.h.

Definition at line 101 of file teleop_nao_joy.h.

Definition at line 102 of file teleop_nao_joy.h.

Definition at line 58 of file teleop_nao_joy.h.

Definition at line 59 of file teleop_nao_joy.h.


The documentation for this class was generated from the following files:


nao_teleop
Author(s): Armin Hornung
autogenerated on Thu Jun 6 2019 21:07:29