simple_bot_goto_position.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, Franco Fusco.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 
36 #include <gtest/gtest.h>
37 #include <ros/ros.h>
38 #include <sensor_msgs/JointState.h>
39 #include <std_msgs/Float64.h>
40 
41 
42 class SimpleBotFixture : public ::testing::Test {
43 protected:
47  double position;
48 
49  void positionCB(const sensor_msgs::JointState& msg) {
50  position = msg.position[0];
51  }
52 
53  bool waitToReachTarget(double target, std::string& err, double precision=5e-2, double timeout=20.0) {
54  position = 1e3*precision + target; // make position != target
55  ros::Rate rate(20.0);
56  std_msgs::Float64 cmd;
57  cmd.data = target;
59 
60  while(ros::ok()) {
61  pub.publish(cmd);
62  if(std::fabs(target-position) < precision)
63  return true;
64  if( (ros::Time::now()-start).toSec() > timeout ) {
65  err = "Timed out, target = " + std::to_string(target) + ", current = " + std::to_string(position);
66  return false;
67  }
68  rate.sleep();
69  }
70 
71  err = "ROS shutdwon, target = " + std::to_string(target) + ", current = " + std::to_string(position);
72  return false;
73  }
74 
75 
76  void SetUp() override {
77  // setup
78  position = 0.0;
79  pub = nh.advertise<std_msgs::Float64>("position_controller/command", 1);
80  sub = nh.subscribe("joint_states", 1, &SimpleBotFixture::positionCB, this);
81  }
82 };
83 
84 
85 TEST_F(SimpleBotFixture, TestPosition) {
86  ros::Duration(1.0).sleep();
87  std::string err;
88  EXPECT_TRUE(waitToReachTarget(1.0, err)) << err;
89  EXPECT_TRUE(waitToReachTarget(-1.0, err)) << err;
90  EXPECT_TRUE(waitToReachTarget(0.0, err)) << err;
91 }
92 
93 
94 int main(int argc, char** argv) {
95  testing::InitGoogleTest(&argc, argv);
96  ros::init(argc, argv, "dummy");
98  spinner.start();
99  int ret = RUN_ALL_TESTS();
100  spinner.stop();
101  ros::shutdown();
102  return ret;
103 }
ROSCPP_DECL void start()
TEST_F(SimpleBotFixture, TestPosition)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
string cmd
bool waitToReachTarget(double target, std::string &err, double precision=5e-2, double timeout=20.0)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void spinner()
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
void positionCB(const sensor_msgs::JointState &msg)
static Time now()
ROSCPP_DECL void shutdown()
bool sleep() const


effort_controllers
Author(s): Vijay Pradeep
autogenerated on Fri Feb 3 2023 03:19:08