#include <ros/ros.h>#include <iostream>#include <cmath>#include <stdexcept>#include "duration.h"#include <sys/time.h>#include "ros/time.h"#include <cstdio>#include <sstream>#include <log4cxx/logger.h>#include "ros/console.h"#include <boost/static_assert.hpp>#include <cassert>#include <stdint.h>#include <assert.h>#include <stddef.h>#include <string>#include "ros/assert.h"#include <vector>#include <map>#include <set>#include <list>#include <boost/shared_ptr.hpp>#include <boost/weak_ptr.hpp>#include <boost/function.hpp>#include "exceptions.h"#include <boost/shared_array.hpp>#include "ros/types.h"#include "ros/forwards.h"#include "ros/common.h"#include "ros/macros.h"#include <string.h>#include <boost/array.hpp>#include "serialized_message.h"#include "message_forward.h"#include <boost/utility/enable_if.hpp>#include <boost/type_traits/remove_const.hpp>#include <boost/type_traits/remove_reference.hpp>#include "message_traits.h"#include "ros/exception.h"#include <boost/call_traits.hpp>#include <boost/mpl/and.hpp>#include <boost/mpl/or.hpp>#include <boost/mpl/not.hpp>#include <cstring>#include <boost/bind.hpp>#include <typeinfo>#include <ros/message.h>#include <boost/type_traits/is_void.hpp>#include <boost/type_traits/is_base_of.hpp>#include <boost/type_traits/is_const.hpp>#include <boost/type_traits/add_const.hpp>#include <boost/make_shared.hpp>#include <ros/static_assert.h>#include "ros/message_traits.h"#include "ros/builtin_message_traits.h"#include "ros/serialization.h"#include "ros/message_event.h"#include "forwards.h"#include "timer_options.h"#include "wall_timer_options.h"#include "ros/service_traits.h"#include <boost/lexical_cast.hpp>#include "subscription_callback_helper.h"#include "ros/spinner.h"#include <time.h>#include "ros/publisher.h"#include <boost/utility.hpp>#include "ros/service_server.h"#include "ros/subscriber.h"#include "ros/node_handle.h"#include "ros/init.h"#include "XmlRpcValue.h"#include "node_handle.h"#include "ros/names.h"#include <iomanip>#include <boost/thread/mutex.hpp>#include <ostream>#include "ros/message_operations.h"#include "std_msgs/Header.h"#include "geometry_msgs/Vector3.h"#include "geometry_msgs/Quaternion.h"#include "geometry_msgs/Point.h"#include "btMatrix3x3.h"#include "tf/exceptions.h"#include "LinearMath/btTransform.h"#include <boost/signals.hpp>#include "geometry_msgs/Pose.h"#include <trajectory_msgs/JointTrajectory.h>#include <sensor_msgs/JointState.h>#include "geometric_shapes_msgs/Shape.h"#include "geometry_msgs/PoseStamped.h"#include "motion_planning_msgs/RobotState.h"#include "motion_planning_msgs/JointConstraint.h"#include "motion_planning_msgs/PositionConstraint.h"#include "motion_planning_msgs/OrientationConstraint.h"#include "geometry_msgs/PointStamped.h"#include "motion_planning_msgs/Constraints.h"#include "motion_planning_msgs/RobotTrajectory.h"#include "motion_planning_msgs/ArmNavigationErrorCodes.h"
Go to the source code of this file.
Namespaces | |
| namespace | motion_planning_msgs |
Functions | |
| std::string | motion_planning_msgs::armNavigationErrorCodeToString (const motion_planning_msgs::ArmNavigationErrorCodes &error_code) |
| Convert an error code into a string value. | |
| bool | motion_planning_msgs::constraintsToPoseStampedVector (const motion_planning_msgs::Constraints &constraints, std::vector< geometry_msgs::PoseStamped > &poses) |
| Extract pose information from a position and orientation constraint into a pose stamped message. | |
| sensor_msgs::JointState | motion_planning_msgs::createJointState (std::vector< std::string > joint_names, std::vector< double > joint_values) |
| Create a joint state from a std vector of names and values. | |
| motion_planning_msgs::JointPath | motion_planning_msgs::jointConstraintsToJointPath (const std::vector< motion_planning_msgs::JointConstraint > &constraints) |
| Extract joint position information from a set of joint constraints into a joint state message. | |
| sensor_msgs::JointState | motion_planning_msgs::jointConstraintsToJointState (const std::vector< motion_planning_msgs::JointConstraint > &constraints) |
| Extract joint position information from a set of joint constraints into a joint state message. | |
| trajectory_msgs::JointTrajectory | motion_planning_msgs::jointConstraintsToJointTrajectory (const std::vector< motion_planning_msgs::JointConstraint > &constraints) |
| Extract joint position information from a set of joint constraints into a joint state message. | |
| trajectory_msgs::JointTrajectory | motion_planning_msgs::jointPathToJointTrajectory (const motion_planning_msgs::JointPath &path) |
| Convert a joint path message to a joint trajectory message. | |
| motion_planning_msgs::JointPathPoint | motion_planning_msgs::jointStateToJointPathPoint (const sensor_msgs::JointState &state) |
| Convert a joint state to a joint path point message. | |
| trajectory_msgs::JointTrajectoryPoint | motion_planning_msgs::jointStateToJointTrajectoryPoint (const sensor_msgs::JointState &state) |
| Convert a joint state to a joint trajectory point message. | |
| motion_planning_msgs::JointPath | motion_planning_msgs::jointTrajectoryToJointPath (const trajectory_msgs::JointTrajectory &trajectory) |
| Convert a joint trajectory message to a joint path message (this conversion will cause loss of velocity and acceleration information). | |
| motion_planning_msgs::MultiDOFJointTrajectoryPoint | motion_planning_msgs::multiDOFJointStateToMultiDOFJointTrajectoryPoint (const motion_planning_msgs::MultiDOFJointState &state) |
| Convert a multi-dof state to a multi-dof joint trajectory point message. | |
| motion_planning_msgs::MultiDOFJointState | motion_planning_msgs::poseConstraintsToMultiDOFJointState (const std::vector< motion_planning_msgs::PositionConstraint > &position_constraints, const std::vector< motion_planning_msgs::OrientationConstraint > &orientation_constraints) |
| Extract pose information from a position and orientation constraint into a multi dof joint state. | |
| geometry_msgs::PoseStamped | motion_planning_msgs::poseConstraintsToPoseStamped (const motion_planning_msgs::PositionConstraint &position_constraint, const motion_planning_msgs::OrientationConstraint &orientation_constraint) |
| Extract pose information from a position and orientation constraint into a pose stamped message. | |
| void | motion_planning_msgs::poseConstraintToPositionOrientationConstraints (const motion_planning_msgs::SimplePoseConstraint &pose_constraint, motion_planning_msgs::PositionConstraint &position_constraint, motion_planning_msgs::OrientationConstraint &orientation_constraint) |
| Convert a simple pose constraint into a position and orientation constraint. | |
| void | motion_planning_msgs::poseStampedToPositionOrientationConstraints (const geometry_msgs::PoseStamped &pose_stamped, const std::string &link_name, motion_planning_msgs::PositionConstraint &position_constraint, motion_planning_msgs::OrientationConstraint &orientation_constraint) |
| Convert a stamped pose into a position and orientation constraint. | |
| void | motion_planning_msgs::printJointState (const sensor_msgs::JointState &joint_state) |
| Print the joint state information. | |
| void | motion_planning_msgs::robotStateToRobotTrajectoryPoint (const motion_planning_msgs::RobotState &state, trajectory_msgs::JointTrajectoryPoint &point, motion_planning_msgs::MultiDOFJointTrajectoryPoint &multi_dof_point) |
| Convert a robot state to a robot trajectory message. | |