pr2_teleop_general_commander.h
Go to the documentation of this file.
1 /*
2  * pr2_teleop_general_commander
3  * Copyright (c) 2008, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the <ORGANIZATION> nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 // Author: E. Gil Jones
32 
33 #include <cstdio>
34 #include <cstdlib>
35 #include <unistd.h>
36 #include <math.h>
37 
38 #include <ros/ros.h>
39 #include <sensor_msgs/Joy.h>
40 
41 #include <sensor_msgs/JointState.h>
42 #include <pr2_msgs/SetPeriodicCmd.h>
43 #include <geometry_msgs/Pose.h>
44 #include <urdf/model.h>
46 #include <pr2_controllers_msgs/PointHeadAction.h>
47 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
48 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
49 #include <pr2_common_action_msgs/TuckArmsAction.h>
50 #include <pr2_msgs/PowerBoardState.h>
51 
52 static const std::string default_arm_controller_name="arm_controller";
53 
55 
56 public:
57 
58  enum WhichArm {
62  };
63 
68  };
69 
75  };
76 
81  };
82 
83  enum HeadSequence {
86  };
87 
88 public:
89 
90  GeneralCommander(bool control_body,
91  bool control_head,
92  bool control_rarm,
93  bool control_larm,
94  bool control_prosilica,
95  std::string arm_controller_name=default_arm_controller_name);
96 
98 
99  void setLaserMode(LaserControlMode mode);
100 
101  void setHeadMode(HeadControlMode mode);
102 
103  void setArmMode(WhichArm which, ArmControlMode mode);
104 
106 
108 
109  //returns right if they are different and both are requested
111 
112  void sendHeadCommand(double req_pan, double req_tilt);
113 
114  void sendProjectorStartStop(bool start);
115 
116  void sendGripperCommand(WhichArm which, bool close);
117 
118  void sendHeadTrackCommand();
119 
120  void sendTorsoCommand(double pos, double vel);
121 
122  void sendBaseCommand(double vx, double vy, double vw);
123 
124  void switchControllers(const std::vector<std::string>& start_controllers, const std::vector<std::string>& stop_controllers);
125 
126  void sendWristVelCommands(double right_wrist_vel, double left_wrist_vel, double hz);
127 
128  bool getJointPosition(const std::string& name, double& pos) const;
129  bool getJointVelocity(const std::string& name, double& vel) const;
130 
132 
133  void sendArmVelCommands(double r_x_vel, double r_y_vel, double r_z_vel, double r_roll_vel, double r_pitch_vel, double r_yaw_vel,
134  double l_x_vel, double l_y_vel, double l_z_vel, double l_roll_vel, double l_pitch_vel, double l_yaw_vel,
135  double hz);
136 
137  bool moveToWalkAlongArmPose();
138 
139  void sendWalkAlongCommand(double thresh,
140  double x_dist_max, double x_speed_scale,
141  double y_dist_max, double y_speed_scale,
142  double rot_scale);
143 
144  void sendHeadSequence(HeadSequence seq);
145 
146  void requestProsilicaImage(std::string ns);
147 
148  bool initWalkAlong();
149 
150  void tuckArms(WhichArm arm);
151  void untuckArms(WhichArm arm);
152 
153  bool isWalkAlongOk() {
154  return walk_along_ok_;
155  }
156 
158  walk_along_ok_ = false;
159  }
160 
161 private:
162 
163  geometry_msgs::Pose getPositionFromJointsPose(ros::ServiceClient& service_client,
164  std::string fk_link,
165  const std::vector<std::string>& joint_names, const std::vector<double>& joint_pos);
166 
168 
169  void jointStateCallback(const sensor_msgs::JointStateConstPtr &jointState);
170 
171  void powerBoardCallback(const pr2_msgs::PowerBoardStateConstPtr &powerBoardState);
172 
173  void composeWristRotGoal(const std::string pref, pr2_controllers_msgs::JointTrajectoryGoal& goal,
174  std::vector<double>& des_joints, double des_vel, double hz) const;
175 
176  void clampDesiredArmPositionsToActual(double max_dist);
177 
178  double calcAverage(const std::list<double>& av_list) const;
179 
180  void unnormalizeTrajectory(trajectory_msgs::JointTrajectory& traj) const;
181 
183 
189 
193 
197 
200 
201  std::map<std::string, double> joint_state_position_map_;
202  std::map<std::string, double> joint_state_velocity_map_;
203 
206 
209 
211 
214 
215  trajectory_msgs::JointTrajectory head_nod_traj_, head_shake_traj_;
216 
231 
234 
236 
241 
247 
254 };
GeneralCommander::des_r_wrist_roll_pose_
geometry_msgs::Pose des_r_wrist_roll_pose_
Definition: pr2_teleop_general_commander.h:205
GeneralCommander::requestProsilicaImage
void requestProsilicaImage(std::string ns)
Definition: pr2_teleop_general_commander.cpp:1546
GeneralCommander::des_l_wrist_roll_pose_
geometry_msgs::Pose des_l_wrist_roll_pose_
Definition: pr2_teleop_general_commander.h:205
GeneralCommander::right_arm_kinematics_inverse_client_
ros::ServiceClient right_arm_kinematics_inverse_client_
Definition: pr2_teleop_general_commander.h:220
GeneralCommander::control_larm_
bool control_larm_
Definition: pr2_teleop_general_commander.h:187
GeneralCommander::control_rarm_
bool control_rarm_
Definition: pr2_teleop_general_commander.h:186
GeneralCommander::sendHeadTrackCommand
void sendHeadTrackCommand()
Definition: pr2_teleop_general_commander.cpp:497
GeneralCommander::ARM_MANNEQUIN_MODE
@ ARM_MANNEQUIN_MODE
Definition: pr2_teleop_general_commander.h:66
ros::Publisher
GeneralCommander::LASER_TILT_OFF
@ LASER_TILT_OFF
Definition: pr2_teleop_general_commander.h:78
GeneralCommander::switch_controllers_service_
ros::ServiceClient switch_controllers_service_
Definition: pr2_teleop_general_commander.h:218
GeneralCommander::sendHeadCommand
void sendHeadCommand(double req_pan, double req_tilt)
Definition: pr2_teleop_general_commander.cpp:477
GeneralCommander::base_pub_
ros::Publisher base_pub_
Definition: pr2_teleop_general_commander.h:226
GeneralCommander::power_board_sub_
ros::Subscriber power_board_sub_
Definition: pr2_teleop_general_commander.h:230
GeneralCommander::right_wrist_roll_pose_
geometry_msgs::Pose right_wrist_roll_pose_
Definition: pr2_teleop_general_commander.h:204
GeneralCommander::left_arm_traj_pub_
ros::Publisher left_arm_traj_pub_
Definition: pr2_teleop_general_commander.h:228
GeneralCommander::control_head_
bool control_head_
Definition: pr2_teleop_general_commander.h:185
GeneralCommander::~GeneralCommander
~GeneralCommander()
Definition: pr2_teleop_general_commander.cpp:262
GeneralCommander::jointStateCallback
void jointStateCallback(const sensor_msgs::JointStateConstPtr &jointState)
Definition: pr2_teleop_general_commander.cpp:284
GeneralCommander::head_nod_traj_
trajectory_msgs::JointTrajectory head_nod_traj_
Definition: pr2_teleop_general_commander.h:215
ros.h
GeneralCommander::HeadSequence
HeadSequence
Definition: pr2_teleop_general_commander.h:83
GeneralCommander::left_gripper_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > * left_gripper_client_
Definition: pr2_teleop_general_commander.h:250
GeneralCommander::sendProjectorStartStop
void sendProjectorStartStop(bool start)
Definition: pr2_teleop_general_commander.cpp:327
GeneralCommander::robot_model_initialized_
bool robot_model_initialized_
Flag that tells us if the robot model was initialized successfully.
Definition: pr2_teleop_general_commander.h:240
GeneralCommander::setLaserMode
void setLaserMode(LaserControlMode mode)
Definition: pr2_teleop_general_commander.cpp:346
GeneralCommander::walk_rdx_vals_
std::list< double > walk_rdx_vals_
Definition: pr2_teleop_general_commander.h:212
GeneralCommander::HEAD_MANNEQUIN
@ HEAD_MANNEQUIN
Definition: pr2_teleop_general_commander.h:74
GeneralCommander::updateWalkAlongAverages
void updateWalkAlongAverages()
Definition: pr2_teleop_general_commander.cpp:1366
GeneralCommander::getJointVelocity
bool getJointVelocity(const std::string &name, double &vel) const
Definition: pr2_teleop_general_commander.cpp:303
GeneralCommander::torso_pub_
ros::Publisher torso_pub_
Definition: pr2_teleop_general_commander.h:225
GeneralCommander::initWalkAlong
bool initWalkAlong()
Definition: pr2_teleop_general_commander.cpp:1303
GeneralCommander::turnOffWalkAlong
void turnOffWalkAlong()
Definition: pr2_teleop_general_commander.h:157
GeneralCommander::last_torso_vel_
double last_torso_vel_
Definition: pr2_teleop_general_commander.h:235
GeneralCommander::isWalkAlongOk
bool isWalkAlongOk()
Definition: pr2_teleop_general_commander.h:153
GeneralCommander::head_shake_traj_
trajectory_msgs::JointTrajectory head_shake_traj_
Definition: pr2_teleop_general_commander.h:215
GeneralCommander::sendTorsoCommand
void sendTorsoCommand(double pos, double vel)
Definition: pr2_teleop_general_commander.cpp:575
GeneralCommander::last_left_wrist_goal_stamp_
ros::Time last_left_wrist_goal_stamp_
Definition: pr2_teleop_general_commander.h:233
urdf::Model
GeneralCommander::HEAD_SHAKE
@ HEAD_SHAKE
Definition: pr2_teleop_general_commander.h:85
GeneralCommander::LASER_TILT_FAST
@ LASER_TILT_FAST
Definition: pr2_teleop_general_commander.h:80
GeneralCommander::HeadControlMode
HeadControlMode
Definition: pr2_teleop_general_commander.h:70
default_arm_controller_name
static const std::string default_arm_controller_name
Definition: pr2_teleop_general_commander.h:52
GeneralCommander::getLaserMode
LaserControlMode getLaserMode()
Definition: pr2_teleop_general_commander.cpp:311
GeneralCommander::last_right_wrist_goal_stamp_
ros::Time last_right_wrist_goal_stamp_
Definition: pr2_teleop_general_commander.h:232
GeneralCommander::HEAD_JOYSTICK
@ HEAD_JOYSTICK
Definition: pr2_teleop_general_commander.h:71
GeneralCommander::head_pub_
ros::Publisher head_pub_
Definition: pr2_teleop_general_commander.h:224
GeneralCommander::left_des_joint_states_
std::vector< double > left_des_joint_states_
Definition: pr2_teleop_general_commander.h:210
GeneralCommander::walk_along_ok_
bool walk_along_ok_
Definition: pr2_teleop_general_commander.h:213
GeneralCommander::right_gripper_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > * right_gripper_client_
Definition: pr2_teleop_general_commander.h:249
GeneralCommander::laser_control_mode_
LaserControlMode laser_control_mode_
Definition: pr2_teleop_general_commander.h:243
GeneralCommander::sendGripperCommand
void sendGripperCommand(WhichArm which, bool close)
Definition: pr2_teleop_general_commander.cpp:536
GeneralCommander::getPositionFromJointsPose
geometry_msgs::Pose getPositionFromJointsPose(ros::ServiceClient &service_client, std::string fk_link, const std::vector< std::string > &joint_names, const std::vector< double > &joint_pos)
Definition: pr2_teleop_general_commander.cpp:1495
GeneralCommander::r_arm_controller_name_
std::string r_arm_controller_name_
Definition: pr2_teleop_general_commander.h:198
actionlib::SimpleActionClient< pr2_controllers_msgs::PointHeadAction >
GeneralCommander::GeneralCommander
GeneralCommander(bool control_body, bool control_head, bool control_rarm, bool control_larm, bool control_prosilica, std::string arm_controller_name=default_arm_controller_name)
Definition: pr2_teleop_general_commander.cpp:68
GeneralCommander::laser_slow_offset_
double laser_slow_offset_
Definition: pr2_teleop_general_commander.h:192
GeneralCommander::laser_fast_offset_
double laser_fast_offset_
Definition: pr2_teleop_general_commander.h:196
GeneralCommander::ARMS_RIGHT
@ ARMS_RIGHT
Definition: pr2_teleop_general_commander.h:60
GeneralCommander::left_arm_kinematics_inverse_client_
ros::ServiceClient left_arm_kinematics_inverse_client_
Definition: pr2_teleop_general_commander.h:222
GeneralCommander::tilt_laser_service_
ros::ServiceClient tilt_laser_service_
Definition: pr2_teleop_general_commander.h:217
simple_action_client.h
GeneralCommander::HEAD_TRACK_LEFT_HAND
@ HEAD_TRACK_LEFT_HAND
Definition: pr2_teleop_general_commander.h:72
GeneralCommander::head_track_hand_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::PointHeadAction > * head_track_hand_client_
Definition: pr2_teleop_general_commander.h:248
GeneralCommander::sendWalkAlongCommand
void sendWalkAlongCommand(double thresh, double x_dist_max, double x_speed_scale, double y_dist_max, double y_speed_scale, double rot_scale)
Definition: pr2_teleop_general_commander.cpp:1406
GeneralCommander::calcAverage
double calcAverage(const std::list< double > &av_list) const
Definition: pr2_teleop_general_commander.cpp:1484
GeneralCommander::ARMS_LEFT
@ ARMS_LEFT
Definition: pr2_teleop_general_commander.h:59
GeneralCommander::left_walk_along_pose_
std::vector< double > left_walk_along_pose_
Definition: pr2_teleop_general_commander.h:208
GeneralCommander::status_projector_on
bool status_projector_on
Definition: pr2_teleop_general_commander.h:242
GeneralCommander::joint_state_sub_
ros::Subscriber joint_state_sub_
Definition: pr2_teleop_general_commander.h:229
GeneralCommander::joint_state_velocity_map_
std::map< std::string, double > joint_state_velocity_map_
Definition: pr2_teleop_general_commander.h:202
model.h
GeneralCommander::l_arm_controller_name_
std::string l_arm_controller_name_
Definition: pr2_teleop_general_commander.h:199
GeneralCommander::getJointPosition
bool getJointPosition(const std::string &name, double &pos) const
Definition: pr2_teleop_general_commander.cpp:295
GeneralCommander::robot_model_
urdf::Model robot_model_
A model of the robot to see which joints wrap around.
Definition: pr2_teleop_general_commander.h:238
GeneralCommander::joint_state_position_map_
std::map< std::string, double > joint_state_position_map_
Definition: pr2_teleop_general_commander.h:201
GeneralCommander::right_arm_traj_pub_
ros::Publisher right_arm_traj_pub_
Definition: pr2_teleop_general_commander.h:227
GeneralCommander::walk_along_right_des_pose_
geometry_msgs::Pose walk_along_right_des_pose_
Definition: pr2_teleop_general_commander.h:207
GeneralCommander::left_arm_kinematics_forward_client_
ros::ServiceClient left_arm_kinematics_forward_client_
Definition: pr2_teleop_general_commander.h:221
ros::ServiceClient
GeneralCommander::walk_along_left_des_pose_
geometry_msgs::Pose walk_along_left_des_pose_
Definition: pr2_teleop_general_commander.h:207
GeneralCommander::WhichArm
WhichArm
Definition: pr2_teleop_general_commander.h:58
GeneralCommander::moveToWalkAlongArmPose
bool moveToWalkAlongArmPose()
Definition: pr2_teleop_general_commander.cpp:1155
GeneralCommander::sendHeadSequence
void sendHeadSequence(HeadSequence seq)
Definition: pr2_teleop_general_commander.cpp:1520
GeneralCommander::setArmMode
void setArmMode(WhichArm which, ArmControlMode mode)
Definition: pr2_teleop_general_commander.cpp:403
GeneralCommander::laser_fast_amplitude_
double laser_fast_amplitude_
Definition: pr2_teleop_general_commander.h:195
GeneralCommander::right_arm_kinematics_forward_client_
ros::ServiceClient right_arm_kinematics_forward_client_
Definition: pr2_teleop_general_commander.h:219
GeneralCommander::control_body_
bool control_body_
Definition: pr2_teleop_general_commander.h:184
GeneralCommander::composeWristRotGoal
void composeWristRotGoal(const std::string pref, pr2_controllers_msgs::JointTrajectoryGoal &goal, std::vector< double > &des_joints, double des_vel, double hz) const
Definition: pr2_teleop_general_commander.cpp:660
GeneralCommander::left_arm_control_mode_
ArmControlMode left_arm_control_mode_
Definition: pr2_teleop_general_commander.h:246
GeneralCommander::HEAD_TRACK_RIGHT_HAND
@ HEAD_TRACK_RIGHT_HAND
Definition: pr2_teleop_general_commander.h:73
GeneralCommander::control_prosilica_
bool control_prosilica_
Definition: pr2_teleop_general_commander.h:188
GeneralCommander::right_des_joint_states_
std::vector< double > right_des_joint_states_
Definition: pr2_teleop_general_commander.h:210
GeneralCommander::unnormalizeTrajectory
void unnormalizeTrajectory(trajectory_msgs::JointTrajectory &traj) const
Definition: pr2_teleop_general_commander.cpp:845
GeneralCommander::switchControllers
void switchControllers(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers)
Definition: pr2_teleop_general_commander.cpp:603
GeneralCommander::sendWristVelCommands
void sendWristVelCommands(double right_wrist_vel, double left_wrist_vel, double hz)
Definition: pr2_teleop_general_commander.cpp:627
GeneralCommander::laser_slow_amplitude_
double laser_slow_amplitude_
Definition: pr2_teleop_general_commander.h:191
ros::Time
GeneralCommander::left_arm_trajectory_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > * left_arm_trajectory_client_
Definition: pr2_teleop_general_commander.h:252
GeneralCommander::getHeadMode
HeadControlMode getHeadMode()
Definition: pr2_teleop_general_commander.cpp:315
GeneralCommander::n_
ros::NodeHandle n_
Definition: pr2_teleop_general_commander.h:182
GeneralCommander::sendArmVelCommands
void sendArmVelCommands(double r_x_vel, double r_y_vel, double r_z_vel, double r_roll_vel, double r_pitch_vel, double r_yaw_vel, double l_x_vel, double l_y_vel, double l_z_vel, double l_roll_vel, double l_pitch_vel, double l_yaw_vel, double hz)
Definition: pr2_teleop_general_commander.cpp:903
GeneralCommander::HEAD_NOD
@ HEAD_NOD
Definition: pr2_teleop_general_commander.h:84
GeneralCommander::ARM_POSITION_CONTROL
@ ARM_POSITION_CONTROL
Definition: pr2_teleop_general_commander.h:67
GeneralCommander::prosilica_polling_client_
ros::ServiceClient prosilica_polling_client_
Definition: pr2_teleop_general_commander.h:223
GeneralCommander::ARM_NO_CONTROLLER
@ ARM_NO_CONTROLLER
Definition: pr2_teleop_general_commander.h:65
GeneralCommander::walk_rdy_vals_
std::list< double > walk_rdy_vals_
Definition: pr2_teleop_general_commander.h:212
GeneralCommander::laser_slow_period_
double laser_slow_period_
Definition: pr2_teleop_general_commander.h:190
GeneralCommander::setHeadMode
void setHeadMode(HeadControlMode mode)
Definition: pr2_teleop_general_commander.cpp:380
GeneralCommander::laser_fast_period_
double laser_fast_period_
Definition: pr2_teleop_general_commander.h:194
GeneralCommander::walk_ldy_vals_
std::list< double > walk_ldy_vals_
Definition: pr2_teleop_general_commander.h:212
GeneralCommander::ArmControlMode
ArmControlMode
Definition: pr2_teleop_general_commander.h:64
GeneralCommander::right_walk_along_pose_
std::vector< double > right_walk_along_pose_
Definition: pr2_teleop_general_commander.h:208
GeneralCommander::updateCurrentWristPositions
void updateCurrentWristPositions()
Definition: pr2_teleop_general_commander.cpp:695
GeneralCommander::tuck_arms_client_
actionlib::SimpleActionClient< pr2_common_action_msgs::TuckArmsAction > * tuck_arms_client_
Definition: pr2_teleop_general_commander.h:253
GeneralCommander::untuckArms
void untuckArms(WhichArm arm)
Definition: pr2_teleop_general_commander.cpp:1579
GeneralCommander::left_wrist_roll_pose_
geometry_msgs::Pose left_wrist_roll_pose_
Definition: pr2_teleop_general_commander.h:204
GeneralCommander::tuckArms
void tuckArms(WhichArm arm)
Definition: pr2_teleop_general_commander.cpp:1556
GeneralCommander::LASER_TILT_SLOW
@ LASER_TILT_SLOW
Definition: pr2_teleop_general_commander.h:79
GeneralCommander::clampDesiredArmPositionsToActual
void clampDesiredArmPositionsToActual(double max_dist)
Definition: pr2_teleop_general_commander.cpp:770
GeneralCommander::powerBoardCallback
void powerBoardCallback(const pr2_msgs::PowerBoardStateConstPtr &powerBoardState)
Definition: pr2_teleop_general_commander.cpp:1537
GeneralCommander::sendBaseCommand
void sendBaseCommand(double vx, double vy, double vw)
Definition: pr2_teleop_general_commander.cpp:593
GeneralCommander::walk_ldx_vals_
std::list< double > walk_ldx_vals_
Definition: pr2_teleop_general_commander.h:212
GeneralCommander::LaserControlMode
LaserControlMode
Definition: pr2_teleop_general_commander.h:77
ros::NodeHandle
ros::Subscriber
GeneralCommander::getArmMode
ArmControlMode getArmMode(WhichArm which)
Definition: pr2_teleop_general_commander.cpp:319
GeneralCommander::head_control_mode_
HeadControlMode head_control_mode_
Definition: pr2_teleop_general_commander.h:244
GeneralCommander::right_arm_trajectory_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > * right_arm_trajectory_client_
Definition: pr2_teleop_general_commander.h:251
GeneralCommander::ARMS_BOTH
@ ARMS_BOTH
Definition: pr2_teleop_general_commander.h:61
GeneralCommander::right_arm_control_mode_
ArmControlMode right_arm_control_mode_
Definition: pr2_teleop_general_commander.h:245
GeneralCommander
Definition: pr2_teleop_general_commander.h:54


pr2_teleop_general
Author(s): Gil Jones
autogenerated on Thu Aug 18 2022 02:27:06