test_run_base_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
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 #include <pr2_mechanism_controllers/Pose3D.h>
36 #include <ros/node.h>
37 #include <nav_msgs/Odometry.h>
38 #include <geometry_msgs/Twist.h>
39 #include <nav_msgs/Odometry.h>
40 #include <geometry_msgs/Quaternion.h>
41 
42 static int done = 0;
43 
44 void finalize(int donecare)
45 {
46  done = 1;
47 }
48 
49 
51 // Return the rotation in Euler angles
52 libTF::Vector GetAsEuler(geometry_msgs::Quaternion quat)
53 {
54  libTF::Vector vec;
55 
56  double squ;
57  double sqx;
58  double sqy;
59  double sqz;
60 
61 // this->Normalize();
62 
63  squ = quat.w * quat.w;
64  sqx = quat.x * quat.x;
65  sqy = quat.y * quat.y;
66  sqz = quat.z * quat.z;
67 
68  // Roll
69  vec.x = atan2(2 * (quat.y*quat.z + quat.w*quat.x), squ - sqx - sqy + sqz);
70 
71  // Pitch
72  vec.y = asin(-2 * (quat.x*quat.z - quat.w * quat.y));
73 
74  // Yaw
75  vec.z = atan2(2 * (quat.x*quat.y + quat.w*quat.z), squ + sqx - sqy - sqz);
76 
77  return vec;
78 }
79 
80 
81 class test_run_base
82 {
83  public:
84 
86 
88 
89  nav_msgs::Odometry ground_truth;
90 
91  nav_msgs::Odometry odom;
92 
94 
96  {
97  subscriber_connected = 1;
98  }
99 
101  {
102 // cout << "Odom:: (" << ground_truth.pos.position.x << "), (" << ground_truth.pos.orientation.x << ")" << std::endl;
103  };
104 
106  {
107 // cout << "Odom:: (" << ground_truth.pos.position.x << "), (" << ground_truth.pos.orientation.x << ")" << std::endl;
108  };
109 };
110 
111 int main( int argc, char** argv )
112 {
113 
114  /*********** Initialize ROS ****************/
115  ros::init(argc,argv);
116  ros::Node *node = new ros::Node("test_run_base_controller");
117 
118 
119  // receive messages from 2dnav stack
120  nav_msgs::Odometry ground_truth;
121 
122  test_run_base tb;
123 
124  node->subscribe("base_pose_ground_truth",tb.ground_truth,&test_run_base::groundTruthMsgReceived,&tb,10);
125 
126  node->subscribe("odom",tb.odom,&test_run_base::odomMsgReceived,&tb,10);
127 
128  signal(SIGINT, finalize);
129  signal(SIGQUIT, finalize);
130  signal(SIGTERM, finalize);
131 
132 
133  /*********** Start moving the robot ************/
134  geometry_msgs::Twist cmd;
135  cmd.linear.x = 0;
136  cmd.linear.y = 0;
137  cmd.linear.z = 0;
138  cmd.angular.x = 0;
139  cmd.angular.y = 0;
140  cmd.angular.z = 0;
141 
142  double run_time = 0;
143  bool run_time_set = false;
144  int file_num = 0;
145 
146  if(argc >= 2)
147  cmd.linear.x = atof(argv[1]);
148 
149  if(argc >= 3)
150  cmd.linear.y = atof(argv[2]);
151 
152  if(argc >= 4)
153  cmd.angular.z = atof(argv[3]);
154 
155  if(argc ==5)
156  {
157  run_time = atof(argv[4]);
158  run_time_set = true;
159  }
160  node->advertise<geometry_msgs::Twist>("cmd_vel",1);
161  sleep(1);
162  node->publish("cmd_vel",cmd);
163  sleep(1);
164 
165  libTF::Vector ground_truth_angles;
166  ros::Time start_time = ros::Time::now();
167  ros::Duration sleep_time(0.01);
168  while(!done)
169  {
170  ros::Duration delta_time = ros::Time::now() - start_time;
171  cout << "Sending out command " << cmd.linear.x << " " << cmd.linear.y << " " << cmd.angular.z << endl;
172  if(run_time_set && delta_time.toSec() > run_time)
173  break;
174  // ang_rates = GetAsEuler(tb.ground_truth.vel.ang_vel);
175  ground_truth_angles = GetAsEuler(tb.ground_truth.pose.pose.orientation);
176  cout << "g:: " << tb.ground_truth.twist.twist.linear.x << " " << tb.ground_truth.twist.twist.linear.y << " " << tb.ground_truth.twist.twist.angular.z << " " << tb.ground_truth.pose.pose.position.x << " " << tb.ground_truth.pose.pose.position.y << " " << ground_truth_angles.z << " " << tb.ground_truth.header.stamp.sec + tb.ground_truth.header.stamp.nsec/1.0e9 << std::endl;
177  cout << "o:: " << tb.odom.twist.twist.linear.x << " " << tb.odom.twist.twist.linear.y << " " << tb.odom.twist.twist.angular.z << " " << tb.odom.pose.pose.position.x << " " << tb.odom.pose.pose.position.y << " " << tf::getYaw(tb.odom.pose.pose.orientation) << " " << tb.odom.header.stamp.sec + tb.odom.header.stamp.nsec/1.0e9 << std::endl;
178  // cout << delta_time.toSec() << " " << run_time << endl;
179  node->publish("cmd_vel",cmd);
180  sleep_time.sleep();
181  }
182 
183 
184 }
int main(int argc, char **argv)
nav_msgs::Odometry ground_truth
libTF::Vector GetAsEuler(geometry_msgs::Quaternion quat)
static double getYaw(const Quaternion &bt_q)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
nav_msgs::Odometry odom
Definition: test_odom.cpp:90
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
static Time now()
static int done
void finalize(int donecare)


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Mon Jun 10 2019 14:26:33