SMACC2
Loading...
Searching...
No Matches
cl_moveit2z Namespace Reference

Classes

class  CbAttachObject
 Client behavior that attaches a collision object to the robot gripper. More...
 
class  CbCircularPivotMotion
 
class  CbCircularPouringMotion
 
class  CbDetachObject
 Client behavior that detaches the currently attached collision object. More...
 
class  CbEndEffectorRotate
 
class  CbExecuteLastTrajectory
 
class  CbMoveCartesianRelative
 
class  CbMoveCartesianRelative2
 
class  CbMoveEndEffector
 
class  CbMoveEndEffectorRelative
 
class  CbMoveEndEffectorTrajectory
 
class  CbMoveJoints
 
class  CbMoveKnownState
 
class  CbMoveLastTrajectoryInitialState
 
class  CbMoveNamedTarget
 
class  CbUndoLastTrajectory
 
class  ClMoveit2z
 
class  CpGraspingComponent
 
class  CpJointSpaceTrajectoryPlanner
 Component for joint space trajectory generation from Cartesian waypoints. More...
 
class  CpMotionPlanner
 Component for centralized motion planning operations. More...
 
class  CpTFListener
 
class  CpTfListener
 Component for shared TF2 transform management across all behaviors. More...
 
class  CpTrajectoryExecutor
 Component for centralized trajectory execution. More...
 
class  CpTrajectoryHistory
 
class  CpTrajectoryVisualizer
 Component for visualizing trajectories as RViz markers. More...
 
struct  EvIncorrectInitialPosition
 
struct  EvJointDiscontinuity
 
struct  EvMoveGroupMotionExecutionFailed
 
struct  EvMoveGroupMotionExecutionSucceded
 
struct  ExecutionOptions
 Configuration options for trajectory execution. More...
 
struct  ExecutionResult
 Result of a trajectory execution operation. More...
 
struct  JointTrajectoryOptions
 Configuration options for joint space trajectory planning. More...
 
struct  JointTrajectoryResult
 Result of a joint space trajectory planning operation. More...
 
struct  PlanningOptions
 Configuration options for motion planning. More...
 
struct  PlanningResult
 Result of a planning operation. More...
 
struct  TfPoseTrack
 
struct  TrajectoryHistoryEntry
 

Enumerations

enum class  ComputeJointTrajectoryErrorCode {
  SUCCESS , INCORRECT_INITIAL_STATE , JOINT_TRAJECTORY_DISCONTINUITY , SUCCESS ,
  INCORRECT_INITIAL_STATE , JOINT_TRAJECTORY_DISCONTINUITY
}
 
enum class  JointTrajectoryErrorCode {
  SUCCESS , INCORRECT_INITIAL_STATE , JOINT_TRAJECTORY_DISCONTINUITY , IK_SOLUTION_FAILED ,
  EMPTY_WAYPOINT_LIST
}
 Error codes for joint space trajectory computation. More...
 
enum class  ComputeJointTrajectoryErrorCode {
  SUCCESS , INCORRECT_INITIAL_STATE , JOINT_TRAJECTORY_DISCONTINUITY , SUCCESS ,
  INCORRECT_INITIAL_STATE , JOINT_TRAJECTORY_DISCONTINUITY
}
 

Functions

std::string currentJointStatesToString (moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map< std::string, double > &targetJoints)
 

Enumeration Type Documentation

◆ ComputeJointTrajectoryErrorCode [1/2]

Enumerator
SUCCESS 
INCORRECT_INITIAL_STATE 
JOINT_TRAJECTORY_DISCONTINUITY 
SUCCESS 
INCORRECT_INITIAL_STATE 
JOINT_TRAJECTORY_DISCONTINUITY 

Definition at line 52 of file cb_move_end_effector_trajectory.hpp.

◆ ComputeJointTrajectoryErrorCode [2/2]

Enumerator
SUCCESS 
INCORRECT_INITIAL_STATE 
JOINT_TRAJECTORY_DISCONTINUITY 
SUCCESS 
INCORRECT_INITIAL_STATE 
JOINT_TRAJECTORY_DISCONTINUITY 

Definition at line 43 of file cb_move_end_effector_trajectory.hpp.

◆ JointTrajectoryErrorCode

Error codes for joint space trajectory computation.

Enumerator
SUCCESS 
INCORRECT_INITIAL_STATE 
JOINT_TRAJECTORY_DISCONTINUITY 
IK_SOLUTION_FAILED 
EMPTY_WAYPOINT_LIST 

Definition at line 43 of file cp_joint_space_trajectory_planner.hpp.

Function Documentation

◆ currentJointStatesToString()

std::string cl_moveit2z::currentJointStatesToString ( moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
std::map< std::string, double > & targetJoints )

Definition at line 49 of file cb_move_joints.cpp.

52{
53 auto state = moveGroupInterface.getCurrentState();
54
55 if (state == nullptr) return std::string();
56
57 auto vnames = state->getVariableNames();
58
59 std::stringstream ss;
60
61 for (auto & tgj : targetJoints)
62 {
63 auto it = std::find(vnames.begin(), vnames.end(), tgj.first);
64 auto index = std::distance(vnames.begin(), it);
65
66 ss << tgj.first << ":" << state->getVariablePosition(index) << std::endl;
67 }
68
69 return ss.str();
70}

References currentJointStatesToString().

Referenced by currentJointStatesToString().

Here is the call graph for this function:
Here is the caller graph for this function: