moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit::core::MoveItErrorCode Class Reference

a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from a function More...

#include <moveit_error_code.h>

Inheritance diagram for moveit::core::MoveItErrorCode:
Inheritance graph
[legend]
Collaboration diagram for moveit::core::MoveItErrorCode:
Collaboration graph
[legend]

Public Member Functions

 MoveItErrorCode ()
 
 MoveItErrorCode (int code)
 
 MoveItErrorCode (const moveit_msgs::msg::MoveItErrorCodes &code)
 
 operator bool () const
 
bool operator== (const int c) const
 
bool operator!= (const int c) const
 

Detailed Description

a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from a function

Definition at line 47 of file moveit_error_code.h.

Constructor & Destructor Documentation

◆ MoveItErrorCode() [1/3]

moveit::core::MoveItErrorCode::MoveItErrorCode ( )
inline

Definition at line 50 of file moveit_error_code.h.

◆ MoveItErrorCode() [2/3]

moveit::core::MoveItErrorCode::MoveItErrorCode ( int  code)
inline

Definition at line 54 of file moveit_error_code.h.

◆ MoveItErrorCode() [3/3]

moveit::core::MoveItErrorCode::MoveItErrorCode ( const moveit_msgs::msg::MoveItErrorCodes &  code)
inline

Definition at line 58 of file moveit_error_code.h.

Member Function Documentation

◆ operator bool()

moveit::core::MoveItErrorCode::operator bool ( ) const
inlineexplicit

Definition at line 62 of file moveit_error_code.h.

◆ operator!=()

bool moveit::core::MoveItErrorCode::operator!= ( const int  c) const
inline

Definition at line 70 of file moveit_error_code.h.

◆ operator==()

bool moveit::core::MoveItErrorCode::operator== ( const int  c) const
inline

Definition at line 66 of file moveit_error_code.h.


The documentation for this class was generated from the following file: