#include <motion_planning_msgs/JointTrajectoryWithLimits.h>#include <trajectory_msgs/JointTrajectory.h>#include <motion_planning_msgs/JointLimits.h>#include <spline_smoother/LSPBTrajectoryMsg.h>#include <spline_smoother/SplineTrajectory.h>#include <angles/angles.h>#include <ros/ros.h>#include <float.h>

Go to the source code of this file.
Namespaces | |
| namespace | spline_smoother |
Functions | |
| template<typename T > | |
| bool | spline_smoother::checkTrajectoryConsistency (T &waypoint_traj) |
| Ensures the consistency of a WaypointTrajWithLimits message, and resizes vel and acc arrays. | |
| template<typename T > | |
| void | spline_smoother::differentiate (const std::vector< T > &x, std::vector< T > &xd) |
| bool | spline_smoother::findSplineSegment (const spline_smoother::LSPBTrajectoryMsg &spline, const double &time, spline_smoother::LSPBTrajectorySegmentMsg &spline_segment, double &segment_time, int start_index=0, int end_index=-1) |
| bool | spline_smoother::findSplineSegment (const spline_smoother::SplineTrajectory &spline, const double &time, spline_smoother::SplineTrajectorySegment &spline_segment, double &segment_time, int start_index=0, int end_index=-1) |
| Internal function that helps determine which spline segment corresponds to an input time. | |
| bool | spline_smoother::getTotalTime (const spline_smoother::LSPBTrajectoryMsg &spline, double &t) |
| Get the total time for the provided spline trajectory. | |
| bool | spline_smoother::getTotalTime (const spline_smoother::SplineTrajectory &spline, double &t) |
| Get the total time for the provided spline trajectory. | |
| double | spline_smoother::jointDiff (const double &from, const double &to, const motion_planning_msgs::JointLimits &limit) |
| An internal helper function that uses information about the joint to compute proper angular differences if the joint is a rotary joint with limits. | |
| bool | spline_smoother::sampleSplineTrajectory (const spline_smoother::LSPBTrajectoryMsg &spline, const std::vector< double > ×, trajectory_msgs::JointTrajectory &traj_out) |
| bool | spline_smoother::sampleSplineTrajectory (const spline_smoother::SplineTrajectory &spline, const std::vector< double > ×, trajectory_msgs::JointTrajectory &traj_out) |
| bool | spline_smoother::sampleSplineTrajectory (const spline_smoother::LSPBTrajectorySegmentMsg &spline, const double &input_time, trajectory_msgs::JointTrajectoryPoint &point_out) |
| bool | spline_smoother::sampleSplineTrajectory (const spline_smoother::SplineTrajectorySegment &spline, const double &input_time, trajectory_msgs::JointTrajectoryPoint &point_out) |
| template<typename T > | |
| void | spline_smoother::tridiagonalSolve (std::vector< T > &a, std::vector< T > &b, std::vector< T > &c, std::vector< T > &d, std::vector< T > &x) |
| Solves the tridiagonal system of equations, Ax = d A is an n by n square matrix which consists of: diagonal b (0 ... n-1) upper diagonal c (0 ... n-2) lower diagonal a (0 ... n-1). | |
| bool | spline_smoother::write (const spline_smoother::LSPBTrajectoryMsg &spline, const std::vector< double > ×, const std::string &filename) |
| Write the trajectory out to a file after sampling at the specified times. | |
| bool | spline_smoother::write (const spline_smoother::SplineTrajectory &spline, const std::vector< double > ×, const std::string &filename) |
| Write the trajectory out to a file after sampling at the specified times. | |
| bool | spline_smoother::writeSpline (const spline_smoother::LSPBTrajectoryMsg &spline, const std::string &filename) |
| Write the spline representation of the trajectory out. | |
| bool | spline_smoother::writeSpline (const spline_smoother::SplineTrajectory &spline, const std::string &filename) |
| Write the spline representation of the trajectory out. | |
Variables | |
| static const double | spline_smoother::MAX_ALLOWABLE_TIME = FLT_MAX |