17 #include <gtest/gtest.h>
19 #include <trajectory_msgs/JointTrajectory.h>
20 #include <control_msgs/FollowJointTrajectoryAction.h>
28 void SetUp()
override;
41 const std::string action_server_name = nh.
getNamespace() +
"/manipulator_joint_trajectory_controller/"
42 "follow_joint_trajectory";
45 ASSERT_TRUE(action_client.
waitForServer(WAIT_FOR_ACTION_SERVER_TIME));
48 control_msgs::FollowJointTrajectoryGoal goal;
49 trajectory_msgs::JointTrajectory traj;
50 trajectory_msgs::JointTrajectoryPoint traj_point;
51 traj_point.positions = { 0.0, 1.0, 0.0, 0.0, 0.0, 0.0 };
53 traj.points.push_back(traj_point);
54 traj.joint_names = {
"prbt_joint_1",
"prbt_joint_2",
"prbt_joint_3",
"prbt_joint_4",
"prbt_joint_5",
"prbt_joint_6" };
55 goal.trajectory = traj;
62 int main(
int argc,
char** argv)
64 ros::init(argc, argv,
"integrationtest_gazebo_bringup");
67 testing::InitGoogleTest(&argc, argv);
68 return RUN_ALL_TESTS();