35 #include <pr2_mechanism_controllers/Pose3D.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> 63 squ = quat.w * quat.w;
64 sqx = quat.x * quat.x;
65 sqy = quat.y * quat.y;
66 sqz = quat.z * quat.z;
69 vec.x =
atan2(2 * (quat.y*quat.z + quat.w*quat.x), squ - sqx - sqy + sqz);
72 vec.y =
asin(-2 * (quat.x*quat.z - quat.w * quat.y));
75 vec.z =
atan2(2 * (quat.x*quat.y + quat.w*quat.z), squ + sqx - sqy - sqz);
91 nav_msgs::Odometry
odom;
97 subscriber_connected = 1;
116 ros::Node *node =
new ros::Node(
"test_run_base_controller");
134 geometry_msgs::Twist
cmd;
143 bool run_time_set =
false;
147 cmd.linear.x = atof(argv[1]);
150 cmd.linear.y = atof(argv[2]);
153 cmd.angular.z = atof(argv[3]);
157 run_time = atof(argv[4]);
160 node->advertise<geometry_msgs::Twist>(
"cmd_vel",1);
162 node->publish(
"cmd_vel",cmd);
165 libTF::Vector ground_truth_angles;
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)
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;
179 node->publish(
"cmd_vel",cmd);
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)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void groundTruthMsgReceived()
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
void subscriber_connect()
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void finalize(int donecare)