Class RobotModeData
Defined in File robot_mode_data.h
Inheritance Relationships
Base Type
public urcl::primary_interface::RobotState
(Class RobotState)
Class Documentation
-
class RobotModeData : public urcl::primary_interface::RobotState
This messages contains data about the mode of the robot.
Public Functions
-
RobotModeData() = delete
-
inline RobotModeData(const RobotStateType type)
Creates a new RobotModeData object.
- Parameters:
type – The type of RobotState message received
-
RobotModeData(const RobotModeData &pkg)
Creates a copy of a RobotModeData object.
- Parameters:
pkg – The RobotModeData object to be copied
-
virtual ~RobotModeData() = default
-
virtual bool parseWith(comm::BinParser &bp)
Sets the attributes of the package by parsing a serialized representation of the package.
- Parameters:
bp – A parser containing a serialized version of the package
- Returns:
True, if the package was parsed successfully, false otherwise
-
virtual bool consumeWith(AbstractPrimaryConsumer &consumer)
Consume this specific package with a specific consumer.
- Parameters:
consumer – Placeholder for the consumer calling this
- Returns:
true on success
-
virtual std::string toString() const
Produces a human readable representation of the package object.
- Returns:
A string representing the object
Public Members
-
uint64_t timestamp_
-
bool is_real_robot_connected_
-
bool is_real_robot_enabled_
-
bool is_robot_power_on_
-
bool is_emergency_stopped_
-
bool is_protective_stopped_
-
bool is_program_running_
-
bool is_program_paused_
-
int8_t robot_mode_
-
uint8_t control_mode_
-
double target_speed_fraction_
-
double speed_scaling_
-
double target_speed_fraction_limit_
-
std::string reserved_
-
RobotModeData() = delete