#include <trajectory_stats.h>
Public Member Functions | |
double | getAngularDistance () |
returns the sum of the angular movements (in radians) by every joint in the arm as it moves through the trajectory. Linear interpolation is used to calculate this metric. | |
double | getCartesianDistance (planning_scene_utils::MotionPlanRequestData &motion_plan_req) |
Returns the cartesian distance (in meters) travelled by the end effector as it moves through the trajectory. Linear interpolation is used to calculate this metric. | |
ros::Duration | getExecutionDuration () |
returns the (estimated/actual) duration of the trajectory (time between start and goal points). Note, if the trajectory does not have valid timestamps, the return value will probably be zero duration. | |
double | getMaxAngularError (trajectory_msgs::JointTrajectory &trajectory_error) |
returns the maximum angular error over all joints for all points on the trajectory This is useful for determining how well the controller executed the trajectory. | |
TrajectoryStats (trajectory_msgs::JointTrajectory &trajectory) | |
Protected Attributes | |
trajectory_msgs::JointTrajectory & | trajectory_ |
class TrajectoryStats analyzes a trajectory and returns statistics. Some of these statistics require extra information, such as the planning scene, and/or the motion plan request. All new statistics should be added to this class (or subclasses).
Definition at line 54 of file trajectory_stats.h.
planning_scene_utils::TrajectoryStats::TrajectoryStats | ( | trajectory_msgs::JointTrajectory & | trajectory | ) | [inline] |
Definition at line 60 of file trajectory_stats.h.
double TrajectoryStats::getAngularDistance | ( | ) |
returns the sum of the angular movements (in radians) by every joint in the arm as it moves through the trajectory. Linear interpolation is used to calculate this metric.
Definition at line 60 of file trajectory_stats.cpp.
double TrajectoryStats::getCartesianDistance | ( | planning_scene_utils::MotionPlanRequestData & | motion_plan_req | ) |
Returns the cartesian distance (in meters) travelled by the end effector as it moves through the trajectory. Linear interpolation is used to calculate this metric.
Definition at line 89 of file trajectory_stats.cpp.
returns the (estimated/actual) duration of the trajectory (time between start and goal points). Note, if the trajectory does not have valid timestamps, the return value will probably be zero duration.
Definition at line 47 of file trajectory_stats.cpp.
double TrajectoryStats::getMaxAngularError | ( | trajectory_msgs::JointTrajectory & | trajectory_error | ) |
returns the maximum angular error over all joints for all points on the trajectory This is useful for determining how well the controller executed the trajectory.
Definition at line 138 of file trajectory_stats.cpp.
trajectory_msgs::JointTrajectory& planning_scene_utils::TrajectoryStats::trajectory_ [protected] |
Definition at line 57 of file trajectory_stats.h.