47using Joints = std::vector<const moveit::core::JointModel*>;
 
   59  std::vector<double> positions;
 
   60  for (
const auto& joint : joints)
 
 
   79  for (
size_t joint_index = 0; joint_index < joints.size(); ++joint_index)
 
 
   98  assert(
static_cast<std::size_t
>(trajectory_values.rows()) == active_joints.size());
 
  100  for (
int timestep = 0; timestep < trajectory_values.cols(); ++timestep)
 
  102    const auto waypoint = std::make_shared<moveit::core::RobotState>(reference_state);
 
 
  139  Eigen::MatrixXd trajectory_values(active_joints.size(), trajectory.
getWayPointCount());
 
  141  for (
int timestep = 0; timestep < trajectory_values.cols(); ++timestep)
 
  143    const auto& waypoint = trajectory.
getWayPoint(timestep);
 
  144    for (
size_t joint_index = 0; joint_index < active_joints.size(); ++joint_index)
 
  146      trajectory_values(joint_index, timestep) = *waypoint.
getJointPositions(active_joints[joint_index]);
 
  150  return trajectory_values;
 
 
 
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
const double * getJointPositions(const std::string &joint_name) const
 
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
 
void setJointPositions(const std::string &joint_name, const double *position)
 
Maintain a sequence of waypoints and the time durations between these waypoints.
 
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
 
const moveit::core::RobotModelConstPtr & getRobotModel() const
 
RobotTrajectory & clear()
 
const moveit::core::JointModelGroup * getGroup() const
 
std::size_t getWayPointCount() const
 
const moveit::core::RobotState & getWayPoint(std::size_t index) const
 
Eigen::MatrixXd robotTrajectoryToMatrix(const robot_trajectory::RobotTrajectory &trajectory)
 
void fillRobotTrajectory(const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, robot_trajectory::RobotTrajectory &trajectory)
 
void setJointPositions(const Eigen::VectorXd &values, const Joints &joints, moveit::core::RobotState &state)
 
std::vector< const moveit::core::JointModel * > Joints
 
robot_trajectory::RobotTrajectory matrixToRobotTrajectory(const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, const moveit::core::JointModelGroup *group=nullptr)
 
std::vector< double > getPositions(const moveit::core::RobotState &state, const Joints &joints)