39 #include <sensor_msgs/Joy.h> 41 #include <sensor_msgs/JointState.h> 42 #include <pr2_msgs/SetPeriodicCmd.h> 43 #include <geometry_msgs/Pose.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> 94 bool control_prosilica,
124 void switchControllers(
const std::vector<std::string>& start_controllers,
const std::vector<std::string>& stop_controllers);
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,
140 double x_dist_max,
double x_speed_scale,
141 double y_dist_max,
double y_speed_scale,
165 const std::vector<std::string>&
joint_names,
const std::vector<double>& joint_pos);
173 void composeWristRotGoal(
const std::string pref, pr2_controllers_msgs::JointTrajectoryGoal& goal,
174 std::vector<double>& des_joints,
double des_vel,
double hz)
const;
178 double calcAverage(
const std::list<double>& av_list)
const;
void sendWalkAlongCommand(double thresh, double x_dist_max, double x_speed_scale, double y_dist_max, double y_speed_scale, double rot_scale)
ros::Subscriber joint_state_sub_
double laser_fast_amplitude_
void switchControllers(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers)
ros::ServiceClient left_arm_kinematics_inverse_client_
double laser_slow_amplitude_
ArmControlMode left_arm_control_mode_
std::string l_arm_controller_name_
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_
void tuckArms(WhichArm arm)
static const std::string default_arm_controller_name
void clampDesiredArmPositionsToActual(double max_dist)
HeadControlMode getHeadMode()
std::list< double > walk_ldx_vals_
double laser_slow_period_
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_
void updateCurrentWristPositions()
std::list< double > walk_rdy_vals_
ros::ServiceClient switch_controllers_service_
void untuckArms(WhichArm arm)
ros::ServiceClient right_arm_kinematics_inverse_client_
double laser_fast_period_
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_
ros::Subscriber power_board_sub_
void updateWalkAlongAverages()
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 sendHeadTrackCommand()
HeadControlMode head_control_mode_
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)
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > * right_gripper_client_
ros::Time last_left_wrist_goal_stamp_
void setLaserMode(LaserControlMode mode)
std::list< double > walk_rdx_vals_
std::vector< double > left_des_joint_states_
LaserControlMode getLaserMode()
double laser_slow_offset_
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
ros::Publisher left_arm_traj_pub_
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.
std::string r_arm_controller_name_
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)
ros::Publisher torso_pub_
std::map< std::string, double > joint_state_velocity_map_
double laser_fast_offset_
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_
bool moveToWalkAlongArmPose()
actionlib::SimpleActionClient< pr2_controllers_msgs::PointHeadAction > * head_track_hand_client_
std::vector< double > left_walk_along_pose_
ros::Time last_right_wrist_goal_stamp_
geometry_msgs::Pose walk_along_right_des_pose_
ros::Publisher right_arm_traj_pub_