moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Namespaces | Functions
utils.hpp File Reference

Utilities used by the trajectory_cache package. More...

#include <string>
#include <vector>
#include <moveit/move_group_interface/move_group_interface.hpp>
#include <moveit_msgs/msg/constraints.hpp>
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <moveit_msgs/srv/get_cartesian_path.hpp>
#include <tf2_ros/buffer.h>
#include <warehouse_ros/message_collection.h>
Include dependency graph for utils.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  moveit_ros
 
namespace  moveit_ros::trajectory_cache
 

Functions

std::string moveit_ros::trajectory_cache::getWorkspaceFrameId (const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::WorkspaceParameters &workspace_parameters)
 Gets workspace frame ID. If workspace_parameters has no frame ID, fetch it from move_group.
 
std::string moveit_ros::trajectory_cache::getCartesianPathRequestFrameId (const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &path_request)
 Gets cartesian path request frame ID. If path_request has no frame ID, fetch it from move_group.
 
moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::restateInNewFrame (const std::shared_ptr< tf2_ros::Buffer > &tf, const std::string &target_frame, const std::string &source_frame, geometry_msgs::msg::Point *translation, geometry_msgs::msg::Quaternion *rotation, const tf2::TimePoint &lookup_time=tf2::TimePointZero)
 Restates a translation and rotation in a new frame.
 
double moveit_ros::trajectory_cache::getExecutionTime (const moveit_msgs::msg::RobotTrajectory &trajectory)
 Returns the execution time of the trajectory in double seconds.
 
moveit_msgs::srv::GetCartesianPath::Request moveit_ros::trajectory_cache::constructGetCartesianPathRequest (moveit::planning_interface::MoveGroupInterface &move_group, const std::vector< geometry_msgs::msg::Pose > &waypoints, double max_step, double jump_threshold, bool avoid_collisions=true)
 Constructs a GetCartesianPath request.
 
void moveit_ros::trajectory_cache::queryAppendCenterWithTolerance (warehouse_ros::Query &query, const std::string &name, double center, double tolerance)
 Appends a range inclusive query with some tolerance about some center value.
 
void moveit_ros::trajectory_cache::sortJointConstraints (std::vector< moveit_msgs::msg::JointConstraint > &joint_constraints)
 Sorts a vector of joint constraints in-place by joint name.
 
void moveit_ros::trajectory_cache::sortPositionConstraints (std::vector< moveit_msgs::msg::PositionConstraint > &position_constraints)
 Sorts a vector of position constraints in-place by link name.
 
void moveit_ros::trajectory_cache::sortOrientationConstraints (std::vector< moveit_msgs::msg::OrientationConstraint > &orientation_constraints)
 Sorts a vector of orientation constraints in-place by link name.
 
moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendConstraintsAsFetchQueryWithTolerance (warehouse_ros::Query &query, std::vector< moveit_msgs::msg::Constraints > constraints, const moveit::planning_interface::MoveGroupInterface &move_group, double match_tolerance, const std::string &reference_frame_id, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a fetch query, with tolerance.
 
moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendConstraintsAsInsertMetadata (warehouse_ros::Metadata &metadata, std::vector< moveit_msgs::msg::Constraints > constraints, const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &reference_frame_id, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a cache entry's metadata.
 
moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendRobotStateJointStateAsFetchQueryWithTolerance (warehouse_ros::Query &query, const moveit_msgs::msg::RobotState &robot_state, const moveit::planning_interface::MoveGroupInterface &move_group, double match_tolerance, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a fetch query, with tolerance.
 
moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendRobotStateJointStateAsInsertMetadata (warehouse_ros::Metadata &metadata, const moveit_msgs::msg::RobotState &robot_state, const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a cache entry's metadata.
 

Detailed Description

Utilities used by the trajectory_cache package.

Author
methylDragon

Definition in file utils.hpp.