37 #ifndef MOVEIT_ROBOT_TRAJECTORY_KINEMATIC_TRAJECTORY_ 38 #define MOVEIT_ROBOT_TRAJECTORY_KINEMATIC_TRAJECTORY_ 42 #include <moveit_msgs/RobotTrajectory.h> 43 #include <moveit_msgs/RobotState.h> 180 void insertWayPoint(std::size_t index,
const robot_state::RobotStatePtr& state,
double dt)
198 size_t end_index = std::numeric_limits<std::size_t>::max());
209 const std::vector<std::string>& joint_filter = std::vector<std::string>())
const;
218 const trajectory_msgs::JointTrajectory& trajectory);
227 const moveit_msgs::RobotTrajectory& trajectory);
237 const moveit_msgs::RobotTrajectory& trajectory);
Core components of MoveIt!
void swap(robot_trajectory::RobotTrajectory &other)
robot_state::RobotStatePtr & getWayPointPtr(std::size_t index)
std::deque< robot_state::RobotStatePtr > waypoints_
void setGroupName(const std::string &group_name)
const robot_model::JointModelGroup * group_
double getDuration() const
robot_model::RobotModelConstPtr robot_model_
RobotTrajectory(const robot_model::RobotModelConstPtr &robot_model, const std::string &group)
robot_state::RobotStatePtr & getFirstWayPointPtr()
std::size_t getWayPointCount() const
const std::string & getGroupName() const
const robot_model::JointModelGroup * getGroup() const
Maintain a sequence of waypoints and the time durations between these waypoints.
void addPrefixWayPoint(const robot_state::RobotState &state, double dt)
void insertWayPoint(std::size_t index, const robot_state::RobotState &state, double dt)
bool getStateAtDurationFromStart(const double request_duration, robot_state::RobotStatePtr &output_state) const
Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time interpolation.
void setWayPointDurationFromPrevious(std::size_t index, double value)
const robot_model::RobotModelConstPtr & getRobotModel() const
const robot_state::RobotState & getLastWayPoint() const
robot_state::RobotStatePtr & getLastWayPointPtr()
void addSuffixWayPoint(const robot_state::RobotStatePtr &state, double dt)
Add a point to the trajectory.
void findWayPointIndicesForDurationAfterStart(const double &duration, int &before, int &after, double &blend) const
Finds the waypoint indicies before and after a duration from start.
const std::deque< double > & getWayPointDurations() const
double getWaypointDurationFromStart(std::size_t index) const
Representation of a robot's state. This includes position, velocity, acceleration and effort...
void addPrefixWayPoint(const robot_state::RobotStatePtr &state, double dt)
double getWayPointDurationFromPrevious(std::size_t index) const
void addSuffixWayPoint(const robot_state::RobotState &state, double dt)
Add a point to the trajectory.
const robot_state::RobotState & getWayPoint(std::size_t index) const
void insertWayPoint(std::size_t index, const robot_state::RobotStatePtr &state, double dt)
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
void setRobotTrajectoryMsg(const robot_state::RobotState &reference_state, const trajectory_msgs::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
const robot_state::RobotState & getFirstWayPoint() const
std::deque< double > duration_from_previous_
double getAverageSegmentDuration() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
void append(const RobotTrajectory &source, double dt, size_t start_index=0, size_t end_index=std::numeric_limits< std::size_t >::max())
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_in...
MOVEIT_CLASS_FORWARD(RobotTrajectory)