#include <trajectory_stats.h>
Static Public Member Functions | |
static double | distance (const trajectory_msgs::JointTrajectoryPoint &point, const trajectory_msgs::JointTrajectoryPoint &point2, const std::vector< std::string > joint_names=std::vector< std::string >()) |
returns the sum of the differences of all joints angular difference between two trajectories Pass in the joint names if you want the values to show up in the log. | |
static double | getAngularDistance (const trajectory_msgs::JointTrajectory &trajectory, unsigned int startIndex=0) |
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. startIndex allows calculation of this metric starting midway through the trajectory | |
static ros::Duration | getDuration (const trajectory_msgs::JointTrajectory &trajectory) |
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. | |
static double | getMaxAngularVelocity (const trajectory_msgs::JointTrajectory &trajectory, unsigned int startIndex=0) |
returns the max of the angular velocities (in radians) by every joint in the arm as it moves through the trajectory. Linear interpolation is used to calculate this metric. startIndex allows calculation of this metric starting midway through the trajectory |
class TrajectoryStats A collection of static routines that analyze a trajectory and returns statistics. Some of these statistics require extra information, such as the planning scene, and/or the motion plan request.
Definition at line 52 of file trajectory_stats.h.
double TrajectoryStats::distance | ( | const trajectory_msgs::JointTrajectoryPoint & | point, |
const trajectory_msgs::JointTrajectoryPoint & | point2, | ||
const std::vector< std::string > | joint_names = std::vector<std::string>() |
||
) | [static] |
returns the sum of the differences of all joints angular difference between two trajectories Pass in the joint names if you want the values to show up in the log.
Definition at line 118 of file trajectory_stats.cpp.
double TrajectoryStats::getAngularDistance | ( | const trajectory_msgs::JointTrajectory & | trajectory, |
unsigned int | startIndex = 0 |
||
) | [static] |
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. startIndex allows calculation of this metric starting midway through the trajectory
Definition at line 59 of file trajectory_stats.cpp.
ros::Duration TrajectoryStats::getDuration | ( | const trajectory_msgs::JointTrajectory & | trajectory | ) | [static] |
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 46 of file trajectory_stats.cpp.
double TrajectoryStats::getMaxAngularVelocity | ( | const trajectory_msgs::JointTrajectory & | trajectory, |
unsigned int | startIndex = 0 |
||
) | [static] |
returns the max of the angular velocities (in radians) by every joint in the arm as it moves through the trajectory. Linear interpolation is used to calculate this metric. startIndex allows calculation of this metric starting midway through the trajectory
Definition at line 85 of file trajectory_stats.cpp.