Go to the documentation of this file.
41 #include <moveit_msgs/RobotTrajectory.h>
42 #include <moveit_msgs/RobotState.h>
228 size_t end_index = std::numeric_limits<std::size_t>::max());
244 const std::vector<std::string>& joint_filter = std::vector<std::string>())
const;
253 const trajectory_msgs::JointTrajectory& trajectory);
262 const moveit_msgs::RobotTrajectory& trajectory);
272 const moveit_msgs::RobotState& state,
273 const moveit_msgs::RobotTrajectory& trajectory);
300 std::deque<moveit::core::RobotStatePtr>
waypoints_;
Core components of MoveIt.
double getWaypointDurationFromStart(std::size_t index) const
std::size_t getWayPointCount() const
const moveit::core::JointModelGroup * getGroup() const
std::chrono::system_clock::duration duration
const std::deque< double > & getWayPointDurations() const
MOVEIT_CLASS_FORWARD(RobotTrajectory)
const moveit::core::RobotModelConstPtr & getRobotModel() const
moveit::core::RobotStatePtr & getFirstWayPointPtr()
RobotTrajectory & setWayPointDurationFromPrevious(std::size_t index, double value)
bool getStateAtDurationFromStart(const double request_duration, moveit::core::RobotStatePtr &output_state) const
Gets a robot state corresponding to a supplied duration from start for the trajectory,...
const moveit::core::JointModelGroup * group_
RobotTrajectory & reverse()
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
double getDuration() const
Maintain a sequence of waypoints and the time durations between these waypoints.
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::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...
RobotTrajectory & operator=(const RobotTrajectory &)=default
std::deque< moveit::core::RobotStatePtr > waypoints_
double path_length(RobotTrajectory const &trajectory)
Calculate the path length of a given trajectory based on the accumulated robot state distances....
moveit::core::RobotModelConstPtr robot_model_
std::deque< double > duration_from_previous_
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & setGroupName(const std::string &group_name)
RobotTrajectory & clear()
moveit::core::RobotStatePtr & getLastWayPointPtr()
void findWayPointIndicesForDurationAfterStart(const double duration, int &before, int &after, double &blend) const
Finds the waypoint indicies before and after a duration from start.
double getWayPointDurationFromPrevious(std::size_t index) const
const moveit::core::RobotState & getLastWayPoint() const
const moveit::core::RobotState & getFirstWayPoint() const
RobotTrajectory(const moveit::core::RobotModelConstPtr &robot_model)
construct a trajectory for the whole robot
double getAverageSegmentDuration() const
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
const std::string & getGroupName() const
RobotTrajectory & unwind()
RobotTrajectory & addPrefixWayPoint(const moveit::core::RobotState &state, double dt)
RobotTrajectory & 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...
void swap(robot_trajectory::RobotTrajectory &other)
RobotTrajectory & insertWayPoint(std::size_t index, const moveit::core::RobotState &state, double dt)
const moveit::core::RobotState & getWayPoint(std::size_t index) const
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15