2 #include <control_msgs/FollowJointTrajectoryAction.h> 7 static const double MIN_POSITIONS [5] = {-3.025528, -0.135228, -1.0, -2.033309, -2.993240};
8 static const double MAX_POSITIONS [5] = {2.891097, 2.168572, 2.054223, 1.876133, 2.870985};
26 traj_client_ =
new TrajClient(
"katana_arm_controller/follow_joint_trajectory",
true);
31 ROS_INFO(
"Waiting for the follow_joint_trajectory server");
52 control_msgs::FollowJointTrajectoryGoal goal;
55 goal.trajectory.joint_names.push_back(
"katana_motor1_pan_joint");
56 goal.trajectory.joint_names.push_back(
"katana_motor2_lift_joint");
57 goal.trajectory.joint_names.push_back(
"katana_motor3_lift_joint");
58 goal.trajectory.joint_names.push_back(
"katana_motor4_lift_joint");
59 goal.trajectory.joint_names.push_back(
"katana_motor5_wrist_roll_joint");
65 goal.trajectory.points[seg].positions.resize(
NUM_JOINTS);
66 goal.trajectory.points[seg].velocities.resize(
NUM_JOINTS);
69 goal.trajectory.points[seg].positions[j] = 0.0;
70 goal.trajectory.points[seg].velocities[j] = 0.0;
76 goal.trajectory.points[seg].positions.resize(NUM_JOINTS);
77 goal.trajectory.points[seg].velocities.resize(NUM_JOINTS);
80 goal.trajectory.points[seg].positions[j] = goal.trajectory.points[seg - 1].positions[j];
81 goal.trajectory.points[seg].velocities[j] = 0.0;
87 assert(NUM_TRAJ_POINTS == 7);
88 goal.trajectory.points[0].positions[moving_joint] = 0.0;
89 goal.trajectory.points[0].time_from_start =
ros::Duration(0.0);
91 goal.trajectory.points[1].positions[moving_joint] =
MIN_POSITIONS[moving_joint];
92 goal.trajectory.points[1].time_from_start =
ros::Duration(2.5);
94 goal.trajectory.points[2].positions[moving_joint] =
MIN_POSITIONS[moving_joint];
95 goal.trajectory.points[2].time_from_start =
ros::Duration(5.5);
97 goal.trajectory.points[3].positions[moving_joint] =
MAX_POSITIONS[moving_joint];
98 goal.trajectory.points[3].time_from_start =
ros::Duration(10.5);
100 goal.trajectory.points[4].positions[moving_joint] =
MAX_POSITIONS[moving_joint];
101 goal.trajectory.points[4].time_from_start =
ros::Duration(13.5);
103 goal.trajectory.points[5].positions[moving_joint] = 0.0;
104 goal.trajectory.points[5].time_from_start =
ros::Duration(16.0);
106 goal.trajectory.points[6].positions[moving_joint] = 0.0;
107 goal.trajectory.points[6].time_from_start =
ros::Duration(19.0);
121 int main(
int argc,
char** argv)
124 ros::init(argc, argv,
"min_max_trajectory");
129 for (
size_t joint = 0; joint <
NUM_JOINTS; joint++)
static const size_t NUM_TRAJ_POINTS
void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal)
Sends the command to start a given trajectory.
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
~RobotArm()
Clean up the action client.
static const double MIN_POSITIONS[5]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajClient
static const size_t NUM_JOINTS
int main(int argc, char **argv)
static const double MAX_POSITIONS[5]
TrajClient * traj_client_
control_msgs::FollowJointTrajectoryGoal armExtensionTrajectory(size_t moving_joint)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
RobotArm()
Initialize the action client and wait for action server to come up.
actionlib::SimpleClientGoalState getState()
Returns the current state of the action.
SimpleClientGoalState getState() const