integrationtest_gazebo_bringup.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 Pilz GmbH & Co. KG
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <gtest/gtest.h>
18 #include <ros/ros.h>
19 #include <trajectory_msgs/JointTrajectory.h>
20 #include <control_msgs/FollowJointTrajectoryAction.h>
22 
23 namespace prbt_gazebo
24 {
25 class GazeboTest : public testing::Test
26 {
27 protected:
28  void SetUp() override;
31 };
32 
34 {
35  spinner_.start();
36 }
37 
38 TEST_F(GazeboTest, basicMove)
39 {
40  ros::NodeHandle nh;
41  const std::string action_server_name = nh.getNamespace() + "/manipulator_joint_trajectory_controller/"
42  "follow_joint_trajectory";
43 
45  ASSERT_TRUE(action_client.waitForServer(WAIT_FOR_ACTION_SERVER_TIME));
46 
47  // Construct the goal
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 };
52  traj_point.time_from_start = ros::Duration(1);
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;
56 
57  ASSERT_EQ(actionlib::SimpleClientGoalState::SUCCEEDED, action_client.sendGoalAndWait(goal).state_);
58 }
59 
60 } // namespace prbt_gazebo
61 
62 int main(int argc, char** argv)
63 {
64  ros::init(argc, argv, "integrationtest_gazebo_bringup");
65  ros::NodeHandle nh;
66 
67  testing::InitGoogleTest(&argc, argv);
68  return RUN_ALL_TESTS();
69 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(GazeboTest, basicMove)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
int main(int argc, char **argv)
const std::string & getNamespace() const


prbt_gazebo
Author(s):
autogenerated on Mon Feb 28 2022 23:14:58