40 geometry_msgs::Twist cmd_vel;
41 cmd_vel.linear.x = 0.0;
42 cmd_vel.angular.z = 0.0;
46 nav_msgs::Odometry old_odom = getLastOdom();
48 cmd_vel.linear.x = 0.1;
53 nav_msgs::Odometry new_odom = getLastOdom();
55 const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp;
57 const double expected_distance = cmd_vel.linear.x * actual_elapsed_time.
toSec();
60 const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
61 const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
62 const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
64 EXPECT_LT(fabs(dz),
EPS);
67 double roll_old, pitch_old, yaw_old;
68 double roll_new, pitch_new, yaw_new;
71 EXPECT_LT(fabs(roll_new - roll_old),
EPS);
72 EXPECT_LT(fabs(pitch_new - pitch_old),
EPS);
73 EXPECT_LT(fabs(yaw_new - yaw_old),
EPS);
74 EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x,
EPS);
75 EXPECT_LT(fabs(new_odom.twist.twist.linear.y),
EPS);
76 EXPECT_LT(fabs(new_odom.twist.twist.linear.z),
EPS);
78 EXPECT_LT(fabs(new_odom.twist.twist.angular.x),
EPS);
79 EXPECT_LT(fabs(new_odom.twist.twist.angular.y),
EPS);
80 EXPECT_LT(fabs(new_odom.twist.twist.angular.z),
EPS);
89 geometry_msgs::Twist cmd_vel;
90 cmd_vel.linear.x = 0.0;
91 cmd_vel.angular.z = 0.0;
95 nav_msgs::Odometry old_odom = getLastOdom();
97 cmd_vel.angular.z = M_PI/10.0;
102 nav_msgs::Odometry new_odom = getLastOdom();
105 EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x),
EPS);
106 EXPECT_LT(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y),
EPS);
107 EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z),
EPS);
109 const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp;
110 const double expected_rotation = cmd_vel.angular.z * actual_elapsed_time.
toSec();
113 double roll_old, pitch_old, yaw_old;
114 double roll_new, pitch_new, yaw_new;
117 EXPECT_LT(fabs(roll_new - roll_old),
EPS);
118 EXPECT_LT(fabs(pitch_new - pitch_old),
EPS);
121 EXPECT_LT(fabs(new_odom.twist.twist.linear.x),
EPS);
122 EXPECT_LT(fabs(new_odom.twist.twist.linear.y),
EPS);
123 EXPECT_LT(fabs(new_odom.twist.twist.linear.z),
EPS);
125 EXPECT_LT(fabs(new_odom.twist.twist.angular.x),
EPS);
126 EXPECT_LT(fabs(new_odom.twist.twist.angular.y),
EPS);
127 EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), expected_rotation/actual_elapsed_time.
toSec(),
EPS);
142 int main(
int argc,
char** argv)
144 testing::InitGoogleTest(&argc, argv);
145 ros::init(argc, argv,
"diff_drive_test");
150 int ret = RUN_ALL_TESTS();
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
ROSCPP_DECL void shutdown()
const double ORIENTATION_TOLERANCE
TEST_F(DiffDriveControllerTest, testForward)
const double POSITION_TOLERANCE