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 };
void sendWalkAlongCommand(double thresh, double x_dist_max, double x_speed_scale, double y_dist_max, double y_speed_scale, double rot_scale)
void switchControllers(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers)
ros::ServiceClient left_arm_kinematics_inverse_client_
ros::ServiceClient tilt_laser_service_
std::vector< double > right_des_joint_states_
void unnormalizeTrajectory(trajectory_msgs::JointTrajectory &traj) const
ros::ServiceClient prosilica_polling_client_
void setHeadMode(HeadControlMode mode)
void sendHeadSequence(HeadSequence seq)
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)
std::list< double > walk_ldy_vals_
void setArmMode(WhichArm which, ArmControlMode mode)
ros::ServiceClient right_arm_kinematics_forward_client_
static const std::string default_arm_controller_name
void clampDesiredArmPositionsToActual(double max_dist)
std::list< double > walk_ldx_vals_
void sendWristVelCommands(double right_wrist_vel, double left_wrist_vel, double hz)
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > * left_arm_trajectory_client_
geometry_msgs::Pose des_l_wrist_roll_pose_
std::list< double > walk_rdy_vals_
ros::ServiceClient switch_controllers_service_
ros::ServiceClient right_arm_kinematics_inverse_client_
void sendBaseCommand(double vx, double vy, double vw)
trajectory_msgs::JointTrajectory head_nod_traj_
std::vector< double > right_walk_along_pose_
actionlib::SimpleActionClient< pr2_common_action_msgs::TuckArmsAction > * tuck_arms_client_
ArmControlMode right_arm_control_mode_
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > * right_arm_trajectory_client_
void sendProjectorStartStop(bool start)
geometry_msgs::Pose des_r_wrist_roll_pose_
geometry_msgs::Pose left_wrist_roll_pose_
geometry_msgs::Pose right_wrist_roll_pose_
void powerBoardCallback(const pr2_msgs::PowerBoardStateConstPtr &powerBoardState)
void jointStateCallback(const sensor_msgs::JointStateConstPtr &jointState)
ArmControlMode getArmMode(WhichArm which)
void sendHeadCommand(double req_pan, double req_tilt)
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > * left_gripper_client_
bool getJointPosition(const std::string &name, double &pos) const
void requestProsilicaImage(std::string ns)
list joint_names
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > * right_gripper_client_
void setLaserMode(LaserControlMode mode)
std::list< double > walk_rdx_vals_
std::vector< double > left_des_joint_states_
double calcAverage(const std::list< double > &av_list) const
void composeWristRotGoal(const std::string pref, pr2_controllers_msgs::JointTrajectoryGoal &goal, std::vector< double > &des_joints, double des_vel, double hz) const
LaserControlMode laser_control_mode_
void sendGripperCommand(WhichArm which, bool close)
void sendTorsoCommand(double pos, double vel)
trajectory_msgs::JointTrajectory head_shake_traj_
bool robot_model_initialized_
Flag that tells us if the robot model was initialized successfully.
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)
std::map< std::string, double > joint_state_velocity_map_
urdf::Model robot_model_
A model of the robot to see which joints wrap around.
std::map< std::string, double > joint_state_position_map_
bool getJointVelocity(const std::string &name, double &vel) const
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)
ros::ServiceClient left_arm_kinematics_forward_client_
geometry_msgs::Pose walk_along_left_des_pose_
actionlib::SimpleActionClient< pr2_controllers_msgs::PointHeadAction > * head_track_hand_client_
std::vector< double > left_walk_along_pose_
geometry_msgs::Pose walk_along_right_des_pose_


pr2_teleop_general
Author(s): Gil Jones
autogenerated on Sat Feb 27 2021 04:01:05