moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <moveit_servo/utils/common.hpp>
Go to the source code of this file.
Namespaces | |
namespace | moveit_servo |
Functions | |
std::optional< std::string > | moveit_servo::getIKSolverBaseFrame (const moveit::core::RobotStatePtr &robot_state, const std::string &group_name) |
Get the base frame of the current active joint group or subgroup's IK solver. | |
std::optional< std::string > | moveit_servo::getIKSolverTipFrame (const moveit::core::RobotStatePtr &robot_state, const std::string &group_name) |
Get the tip (end-effector) frame of the current active joint group or subgroup's IK solver. | |
bool | moveit_servo::isValidCommand (const Eigen::VectorXd &command) |
Checks if a given VectorXd is a valid command. | |
bool | moveit_servo::isValidCommand (const Eigen::Isometry3d &command) |
Checks if a given Isometry3d (pose) is a valid command. | |
bool | moveit_servo::isValidCommand (const TwistCommand &command) |
Checks if a given Twist command is valid. | |
bool | moveit_servo::isValidCommand (const PoseCommand &command) |
Checks if a given Pose command is valid. | |
geometry_msgs::msg::Pose | moveit_servo::poseFromCartesianDelta (const Eigen::VectorXd &delta_x, const Eigen::Isometry3d &base_to_tip_frame_transform) |
Create a pose message for the provided change in Cartesian position. | |
std::optional< trajectory_msgs::msg::JointTrajectory > | moveit_servo::composeTrajectoryMessage (const servo::Params &servo_params, const std::deque< KinematicState > &joint_cmd_rolling_window) |
Create a trajectory message from a rolling window queue of joint state commands. Method optionally returns a trajectory message if one can be created. | |
void | moveit_servo::updateSlidingWindow (KinematicState &next_joint_state, std::deque< KinematicState > &joint_cmd_rolling_window, double max_expected_latency, const rclcpp::Time &cur_time) |
Adds a new joint state command to a queue containing commands over a time window. Also modifies the velocities of the commands to help avoid overshooting. | |
std_msgs::msg::Float64MultiArray | moveit_servo::composeMultiArrayMessage (const servo::Params &servo_params, const KinematicState &joint_state) |
Create a Float64MultiArray message from given joint state. | |
std::pair< double, StatusCode > | moveit_servo::velocityScalingFactorForSingularity (const moveit::core::RobotStatePtr &robot_state, const Eigen::VectorXd &target_delta_x, const servo::Params &servo_params) |
Computes scaling factor for velocity when the robot is near a singularity. | |
double | moveit_servo::jointLimitVelocityScalingFactor (const Eigen::VectorXd &velocities, const moveit::core::JointBoundsVector &joint_bounds, double scaling_override) |
Apply velocity scaling based on joint limits. If the robot model does not have velocity limits defined, then a scale factor of 1.0 will be returned. | |
std::vector< size_t > | moveit_servo::jointVariablesToHalt (const Eigen::VectorXd &positions, const Eigen::VectorXd &velocities, const moveit::core::JointBoundsVector &joint_bounds, const std::vector< double > &margins) |
Finds the joint variable indices corresponding to joints exceeding allowable position limits. | |
geometry_msgs::msg::TransformStamped | moveit_servo::convertIsometryToTransform (const Eigen::Isometry3d &eigen_tf, const std::string &parent_frame, const std::string &child_frame) |
Helper function for converting Eigen::Isometry3d to geometry_msgs/TransformStamped. | |
PoseCommand | moveit_servo::poseFromPoseStamped (const geometry_msgs::msg::PoseStamped &msg) |
Convert a PoseStamped message to a Servo Pose. | |
planning_scene_monitor::PlanningSceneMonitorPtr | moveit_servo::createPlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const servo::Params &servo_params) |
Creates the planning scene monitor used by servo. | |
KinematicState | moveit_servo::extractRobotState (const moveit::core::RobotStatePtr &robot_state, const std::string &move_group_name) |
Extract the state from a RobotStatePtr instance. | |