TrajectoryPlanner.h
Go to the documentation of this file.
00001 
00002 /*
00003  * TrajectoryPlanner.h
00004  *
00005  *  Created on: Feb 22, 2012
00006  *      Author: hess
00007  */
00008 
00009 #ifndef TRAJECTORYPLANNER_H_
00010 #define TRAJECTORYPLANNER_H_
00011 #include <vector>
00012 #include <Eigen/Core>
00013 #include <tf/tf.h>
00014 class TrajectoryPlanner {
00015 public:
00016         TrajectoryPlanner();
00017 
00018         double jointDist(double angle1, double angle2, unsigned int joint);
00019         double absJointConfigurationDist(const std::vector<double>& p1, const std::vector<double>& p2);
00020         void jointConfigurationDifference(const std::vector<double>& p1, const std::vector<double>& p2,
00021                         std::vector<double>& diff);
00022         void absJointConfigurationDifference(const std::vector<double>& p1, const std::vector<double>& p2,
00023                         std::vector<double>& diff);
00024         double jointConfigurationMinTravelTime(const std::vector<double> v1, const std::vector<double> v2);
00025         void getMaxJointVelocities(const std::vector<double> v1, const std::vector<double> v2,
00026                         std::vector<double>& velocities, double& min_time);
00027         void getMaxJointVelocities(const std::vector<double> v1, const std::vector<double> v2, Eigen::VectorXf& velocities, double& min_time);
00028         void planTrajectoryVelocity(const std::vector<std::vector<double> >& joint_traj,
00029         std::vector<std::vector<double> >&vel, std::vector<double>&time, const double scale_t=1, const double scale_v=1 );
00030         void planTrajectoryVelocity(const std::vector<std::vector<double> >& joint_traj,const std::vector<tf::Pose>& pose_traj,
00031         std::vector<std::vector<double> >&vel, std::vector<double>&time, const double scale_t=1, const double scale_v=1 );
00032         void computeGreedyPath(const std::vector<std::vector<std::vector<double> > >& ik_solutions,
00033                         const std::vector<bool>& valid_poses, std::vector<std::vector<double> >& path);
00034     void computeDijkstraPath(const std::vector<std::vector<std::vector<double> > >& ik_solutions,
00035             const std::vector<bool>& valid_poses, std::vector<std::vector<double> >& path, std::string measure);
00036 
00037         std::vector<double> max_velocities_;
00038         std::vector<double> left_limits_;
00039         std::vector<double> right_limits_;
00040 };
00041 
00042 #endif /* TRAJECTORYPLANNER_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


coverage_3d_arm_navigation
Author(s): Juergen Hess
autogenerated on Wed Dec 26 2012 15:25:57