#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/attached_body.h>
#include <sensor_msgs/JointState.h>
#include <visualization_msgs/MarkerArray.h>
#include <std_msgs/ColorRGBA.h>
#include <geometry_msgs/Twist.h>
#include <cassert>
#include <boost/assert.hpp>
Go to the source code of this file.
Classes | |
class | moveit::core::RobotState |
Representation of a robot's state. This includes position, velocity, acceleration and effort. More... | |
Namespaces | |
namespace | moveit |
Main namespace for MoveIt! | |
namespace | moveit::core |
Core components of MoveIt! | |
Typedefs | |
typedef boost::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values) | moveit::core::GroupStateValidityCallbackFn ) |
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_group_variable_values the state is valid or not. Returns true if the state is valid. This call is allowed to modify robot_state (e.g., set joint_group_variable_values) | |
Functions | |
moveit::core::MOVEIT_CLASS_FORWARD (RobotState) | |
std::ostream & | moveit::core::operator<< (std::ostream &out, const RobotState &s) |
Operator overload for printing variable bounds to a stream. |