14 traj_client_(
"/katana_arm_controller/joint_trajectory_action", true), got_joint_state_(false), spinner_(1)
20 joint_names_.push_back(
"katana_motor5_wrist_roll_joint");
28 ROS_INFO(
"Waiting for the joint_trajectory_action server");
38 std::vector<double> ordered_js;
45 for (
size_t j = 0; j < msg->name.size(); ++j)
49 ordered_js[i] = msg->position[j];
73 const size_t NUM_TRAJ_POINTS = 4;
74 const size_t NUM_JOINTS = 5;
77 std::vector<double> calibration_positions(NUM_JOINTS);
78 calibration_positions[0] = -2.96;
79 calibration_positions[1] = 2.14;
80 calibration_positions[2] = -2.16;
81 calibration_positions[3] = -1.97;
82 calibration_positions[4] = -2.93;
85 std::vector<double> straight_up_positions(NUM_JOINTS);
86 straight_up_positions[0] = 0.0;
87 straight_up_positions[1] = 1.57;
88 straight_up_positions[2] = 0.0;
89 straight_up_positions[3] = 0.0;
90 straight_up_positions[4] = 0.0;
92 trajectory_msgs::JointTrajectory trajectory;
105 trajectory.points.resize(NUM_TRAJ_POINTS);
109 trajectory.points[ind].time_from_start =
ros::Duration(5 * ind);
114 trajectory.points[ind].time_from_start =
ros::Duration(5 * ind);
115 trajectory.points[ind].positions = calibration_positions;
119 trajectory.points[ind].time_from_start =
ros::Duration(5 * ind);
120 trajectory.points[ind].positions = straight_up_positions;
124 trajectory.points[ind].time_from_start =
ros::Duration(5 * ind);
125 trajectory.points[ind].positions.resize(NUM_JOINTS);
126 trajectory.points[ind].positions = calibration_positions;
138 control_msgs::JointTrajectoryGoal goal;
139 goal.trajectory = trajectory;
151 int main(
int argc,
char** argv)
154 ros::init(argc, argv,
"pr2_joint_trajectory_client");
ros::AsyncSpinner spinner_
std::vector< std::string > joint_names_
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
virtual ~Pr2JointTrajectoryClient()
#define ROS_INFO_ONCE(...)
void startTrajectory(control_msgs::JointTrajectoryGoal goal)
Sends the command to start a given trajectory.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
control_msgs::JointTrajectoryGoal makeArmUpTrajectory()
std::vector< double > current_joint_state_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber joint_state_sub_
Pr2JointTrajectoryClient()
int main(int argc, char **argv)
actionlib::SimpleClientGoalState getState()
Returns the current state of the action.
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
SimpleClientGoalState getState() const
void jointStateCB(const sensor_msgs::JointState::ConstPtr &msg)