28 #include <control_msgs/JointTrajectoryAction.h> 30 #include <sensor_msgs/JointState.h> 64 std::vector<double> ordered_js;
66 ordered_js.resize(joint_names_.size());
68 for (
size_t i = 0; i < joint_names_.size(); ++i)
71 for (
size_t j = 0; j < msg->name.size(); ++j)
73 if (joint_names_[i] == msg->name[j])
75 ordered_js[i] = msg->position[j];
85 current_joint_state_ = ordered_js;
86 got_joint_state_ =
true;
91 got_joint_state_(false), spinner_(1)
93 joint_names_.push_back(
"katana_l_finger_joint");
94 joint_names_.push_back(
"katana_r_finger_joint");
100 traj_client_ =
new TrajClient(
"katana_arm_controller/gripper_joint_trajectory_action",
true);
105 ROS_INFO(
"Waiting for the joint_trajectory_action server");
108 ROS_INFO(
"The joint_trajectory_action server is available");
127 control_msgs::JointTrajectoryGoal goal;
135 goal.trajectory.points.resize(2);
138 goal.trajectory.points[0].positions.resize(2);
139 goal.trajectory.points[0].velocities.resize(2);
141 goal.trajectory.points[0].positions[0] = current_joint_state_[0];
142 goal.trajectory.points[0].velocities[0] = 0.0;
144 goal.trajectory.points[0].positions[1] = current_joint_state_[1];
145 goal.trajectory.points[0].velocities[1] = 0.0;
147 goal.trajectory.points[0].time_from_start =
ros::Duration(0.0);
152 goal.trajectory.points[1].positions.resize(2);
153 goal.trajectory.points[1].velocities.resize(2);
156 goal.trajectory.points[1].velocities[0] = 0.0;
159 goal.trajectory.points[1].velocities[1] = 0.0;
161 goal.trajectory.points[1].time_from_start =
ros::Duration(3.0);
169 control_msgs::JointTrajectoryGoal goal;
177 goal.trajectory.points.resize(2);
180 goal.trajectory.points[0].positions.resize(2);
181 goal.trajectory.points[0].velocities.resize(2);
183 goal.trajectory.points[0].positions[0] = current_joint_state_[0];
184 goal.trajectory.points[0].velocities[0] = 0.0;
186 goal.trajectory.points[0].positions[1] = current_joint_state_[1];
187 goal.trajectory.points[0].velocities[1] = 0.0;
189 goal.trajectory.points[0].time_from_start =
ros::Duration(0.0);
194 goal.trajectory.points[1].positions.resize(2);
195 goal.trajectory.points[1].velocities.resize(2);
198 goal.trajectory.points[1].velocities[0] = 0.0;
201 goal.trajectory.points[1].velocities[1] = 0.0;
203 goal.trajectory.points[1].time_from_start =
ros::Duration(3.0);
216 int main(
int argc,
char** argv)
220 ros::init(argc, argv,
"test_gripper_joint_trajectory");
224 ROS_INFO(
"Start, press CRTL+C to stop!");
actionlib::SimpleActionClient< control_msgs::JointTrajectoryAction > TrajClient
int main(int argc, char **argv)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
#define ROS_INFO_ONCE(...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleClientGoalState getState()
Returns the current state of the action.
ros::Subscriber joint_state_sub_
static const double GRIPPER_CLOSED_ANGLE
Constants for gripper fully open or fully closed (should be equal to the value in the urdf descriptio...
std::string toString() const
void jointStateCB(const sensor_msgs::JointState::ConstPtr &msg)
control_msgs::JointTrajectoryGoal closeGoal()
std::vector< double > current_joint_state_
static const double GRIPPER_OPEN_ANGLE
Constants for gripper fully open or fully closed (should be equal to the value in the urdf descriptio...
control_msgs::JointTrajectoryGoal openGoal()
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
TrajClient * traj_client_
void startTrajectory(control_msgs::JointTrajectoryGoal goal)
Sends the command to start a given trajectory.
TestGripperJointTrajectory()
SimpleClientGoalState getState() const
~TestGripperJointTrajectory()
A joint angle below this value indicates there is nothing inside the gripper.
std::vector< std::string > joint_names_
ros::AsyncSpinner spinner_