00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <gtest/gtest.h>
00038 #include <spline_smoother/splines.h>
00039 #include <spline_smoother/clamped_cubic_spline_smoother.h>
00040 #include <spline_smoother/numerical_differentiation_spline_smoother.h>
00041 #include <stdlib.h>
00042
00043 using namespace spline_smoother;
00044
00045 TEST(TestClampedCubicSplineSmoother, TestZeroPositionsSmall)
00046 {
00047 int length = ClampedCubicSplineSmoother<motion_planning_msgs::JointTrajectoryWithLimits>::MAX_TRIDIAGONAL_SOLVER_ELEMENTS - 2;
00048
00049 motion_planning_msgs::JointTrajectoryWithLimits wpt;
00050 motion_planning_msgs::JointTrajectoryWithLimits wpt_out;
00051 wpt.trajectory.points.resize(length);
00052 wpt.trajectory.joint_names.resize(1);
00053 wpt.trajectory.joint_names[0] = std::string("test");
00054 for (int i=0; i<length; i++)
00055 {
00056 wpt.trajectory.points[i].positions.resize(1);
00057 wpt.trajectory.points[i].accelerations.resize(1);
00058 wpt.trajectory.points[i].velocities.resize(1);
00059 wpt.trajectory.points[i].positions[0] = 0.0;
00060 wpt.trajectory.points[i].velocities[0] = 0.0;
00061 wpt.trajectory.points[i].accelerations[0] = 0.0;
00062 wpt.trajectory.points[i].time_from_start = ros::Duration(i);
00063 }
00064
00065 ClampedCubicSplineSmoother<motion_planning_msgs::JointTrajectoryWithLimits> ccss;
00066 ccss.smooth(wpt, wpt_out);
00067
00068
00069 for (int i=0; i<length; i++)
00070 {
00071 EXPECT_NEAR(wpt_out.trajectory.points[i].velocities[0], 0.0, 1e-8);
00072 }
00073 }
00074
00075 TEST(TestClampedCubicSplineSmoother, TestStraightLineSmall)
00076 {
00077 int length = ClampedCubicSplineSmoother<motion_planning_msgs::JointTrajectoryWithLimits>::MAX_TRIDIAGONAL_SOLVER_ELEMENTS-2;
00078
00079 motion_planning_msgs::JointTrajectoryWithLimits wpt;
00080 motion_planning_msgs::JointTrajectoryWithLimits wpt_out;
00081 wpt.trajectory.points.resize(length);
00082 wpt.trajectory.joint_names.resize(1);
00083 wpt.trajectory.joint_names[0] = std::string("test");
00084 for (int i=0; i<length; i++)
00085 {
00086 wpt.trajectory.points[i].positions.resize(1);
00087 wpt.trajectory.points[i].accelerations.resize(1);
00088 wpt.trajectory.points[i].velocities.resize(1);
00089 wpt.trajectory.points[i].positions[0] = i;
00090 wpt.trajectory.points[i].velocities[0] = 1.0;
00091 wpt.trajectory.points[i].accelerations[0] = 0.0;
00092 wpt.trajectory.points[i].time_from_start = ros::Duration(i);
00093 }
00094
00095 ClampedCubicSplineSmoother<motion_planning_msgs::JointTrajectoryWithLimits> ccss;
00096 ccss.smooth(wpt, wpt_out);
00097
00098
00099 for (int i=0; i<length; i++)
00100 {
00101 EXPECT_NEAR(wpt.trajectory.points[i].velocities[0], 1.0, 1e-8);
00102 }
00103 }