Classes | |
| class | CollisionCheck |
| class | LowPassFilter |
| struct | PIDConfig |
| class | PoseTracking |
| class | PoseTrackingFixture |
| class | Servo |
| class | ServoCalcs |
| class | ServoFixture |
| struct | ServoParameters |
| class | SpaceNavToTwist |
Typedefs | |
| using | PoseTrackingPtr = std::shared_ptr< PoseTracking > |
| using | ServoPtr = std::shared_ptr< Servo > |
Enumerations | |
| enum | CollisionCheckType { K_THRESHOLD_DISTANCE = 1, K_STOP_DISTANCE = 2 } |
| enum | PoseTrackingStatusCode : int8_t { PoseTrackingStatusCode::INVALID = -1, PoseTrackingStatusCode::SUCCESS = 0, PoseTrackingStatusCode::NO_RECENT_TARGET_POSE = 1, PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE = 2, PoseTrackingStatusCode::STOP_REQUESTED = 3 } |
| enum | StatusCode : int8_t { StatusCode::INVALID = -1, StatusCode::NO_WARNING = 0, StatusCode::DECELERATE_FOR_SINGULARITY = 1, StatusCode::HALT_FOR_SINGULARITY = 2, StatusCode::DECELERATE_FOR_COLLISION = 3, StatusCode::HALT_FOR_COLLISION = 4, StatusCode::JOINT_BOUND = 5 } |
Functions | |
| const std::unordered_map< PoseTrackingStatusCode, std::string > | POSE_TRACKING_STATUS_CODE_MAP ({ { PoseTrackingStatusCode::INVALID, "Invalid" }, { PoseTrackingStatusCode::SUCCESS, "Success" }, { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" }, { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" }, { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } }) |
| const std::unordered_map< StatusCode, std::string > | SERVO_STATUS_CODE_MAP ({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_SINGULARITY, "Close to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } }) |
| TEST_F (PoseTrackingFixture, OutgoingMsgTest) | |
| TEST_F (ServoFixture, EnforceVelLimitsTest) | |
| TEST_F (ServoFixture, JointVelocityEnforcementTest) | |
| TEST_F (ServoFixture, SendJointServoTest) | |
| TEST_F (ServoFixture, SendTwistStampedTest) | |
| TEST_F (ServoFixture, StartStopTest) | |
Variables | |
| static const int | NUM_SPINNERS = 1 |
| static const int | QUEUE_LENGTH = 1 |
| constexpr size_t | ROS_QUEUE_SIZE = 2 |
| using moveit_servo::PoseTrackingPtr = typedef std::shared_ptr<PoseTracking> |
Definition at line 224 of file pose_tracking.h.
| using moveit_servo::ServoPtr = typedef std::shared_ptr<Servo> |
| Enumerator | |
|---|---|
| K_THRESHOLD_DISTANCE | |
| K_STOP_DISTANCE | |
Definition at line 88 of file collision_check.h.
|
strong |
| Enumerator | |
|---|---|
| INVALID | |
| SUCCESS | |
| NO_RECENT_TARGET_POSE | |
| NO_RECENT_END_EFFECTOR_POSE | |
| STOP_REQUESTED | |
Definition at line 97 of file pose_tracking.h.
|
strong |
| Enumerator | |
|---|---|
| INVALID | |
| NO_WARNING | |
| DECELERATE_FOR_SINGULARITY | |
| HALT_FOR_SINGULARITY | |
| DECELERATE_FOR_COLLISION | |
| HALT_FOR_COLLISION | |
| JOINT_BOUND | |
Definition at line 82 of file status_codes.h.
| const std::unordered_map<PoseTrackingStatusCode, std::string> moveit_servo::POSE_TRACKING_STATUS_CODE_MAP | ( | { { PoseTrackingStatusCode::INVALID, "Invalid" }, { PoseTrackingStatusCode::SUCCESS, "Success" }, { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" }, { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" }, { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } } | ) |
| const std::unordered_map<StatusCode, std::string> moveit_servo::SERVO_STATUS_CODE_MAP | ( | { { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_SINGULARITY, "Close to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } } | ) |
| moveit_servo::TEST_F | ( | PoseTrackingFixture | , |
| OutgoingMsgTest | |||
| ) |
Definition at line 101 of file pose_tracking_test.cpp.
| moveit_servo::TEST_F | ( | ServoFixture | , |
| EnforceVelLimitsTest | |||
| ) |
Definition at line 179 of file basic_servo_tests.cpp.
| moveit_servo::TEST_F | ( | ServoFixture | , |
| JointVelocityEnforcementTest | |||
| ) |
Definition at line 192 of file servo_cpp_interface_test.cpp.
| moveit_servo::TEST_F | ( | ServoFixture | , |
| SendJointServoTest | |||
| ) |
Definition at line 136 of file basic_servo_tests.cpp.
| moveit_servo::TEST_F | ( | ServoFixture | , |
| SendTwistStampedTest | |||
| ) |
Definition at line 94 of file basic_servo_tests.cpp.
| moveit_servo::TEST_F | ( | ServoFixture | , |
| StartStopTest | |||
| ) |
Definition at line 97 of file servo_cpp_interface_test.cpp.
|
static |
Definition at line 82 of file spacenav_to_twist.cpp.
|
static |
Definition at line 83 of file spacenav_to_twist.cpp.
|
constexpr |
Definition at line 80 of file servo_parameters.h.