Public Member Functions | Protected Member Functions | Protected Attributes
MotionSafety Class Reference

#include <motion_safety.h>

List of all members.

Public Member Functions

void checkFaults ()
bool isEstopped ()
 MotionSafety ()
 MotionSafety (ros::NodeHandle *nh)
void setStop (const std::string reason, bool estop, bool fault)

Protected Member Functions

void diagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
void driveCallback (const grizzly_msgs::DriveConstPtr &)
void estopCallback (const std_msgs::BoolConstPtr &)
void mcuStatusCallback (const grizzly_msgs::RawStatusConstPtr &)
void watchdogCallback (const ros::TimerEvent &)

Protected Attributes

shared_ptr< DriveChangeLimiteraccel_limiters_ [4]
shared_ptr
< diagnostic_updater::HeaderlessTopicDiagnostic
diag_cmd_drive_freq_
shared_ptr
< diagnostic_updater::HeaderlessTopicDiagnostic
diag_mcu_status_freq_
shared_ptr
< diagnostic_updater::Updater
diagnostic_updater_
shared_ptr< EncodersMonitorencoders_monitor_
double expected_mcu_status_frequency_
ros::Time last_commanded_movement_time_
grizzly_msgs::RawStatusConstPtr last_mcu_status_
ros::Time last_non_precharge_time_
double max_accel_
double max_cmd_drive_freq_
double min_cmd_drive_freq_
shared_ptr< MotorsMonitormotor_drivers_monitor_
ros::NodeHandlenh_
ros::Publisher pub_ambience_
ros::Publisher pub_estop_
ros::Publisher pub_safe_drive_
double radius_
std::string reason_
ros::Duration starting_duration_
MotionState state_
ros::Subscriber sub_drive_
ros::Subscriber sub_mcu_status_
ros::Subscriber sub_user_estop_
ros::Time transition_to_moving_time_
ros::Timer watchdog_timer_
double width_

Detailed Description

Definition at line 82 of file motion_safety.h.


Constructor & Destructor Documentation

Definition at line 85 of file motion_safety.h.

Definition at line 41 of file motion_safety_node.cpp.


Member Function Documentation

Definition at line 108 of file motion_safety_node.cpp.

Definition at line 263 of file motion_safety_node.cpp.

void MotionSafety::driveCallback ( const grizzly_msgs::DriveConstPtr &  drive_commanded) [protected]

Manages a pass-through of Grizzly Drive messages, ensuring that the appropriate delays are observed before allowing the chassis to move, including activating the chassis lights and beeper. Also monitors encoders for possible failure.

Definition at line 231 of file motion_safety_node.cpp.

void MotionSafety::estopCallback ( const std_msgs::BoolConstPtr &  msg) [protected]

Definition at line 217 of file motion_safety_node.cpp.

Definition at line 251 of file motion_safety_node.cpp.

void MotionSafety::mcuStatusCallback ( const grizzly_msgs::RawStatusConstPtr &  status) [protected]

Definition at line 257 of file motion_safety_node.cpp.

void MotionSafety::setStop ( const std::string  reason,
bool  estop = false,
bool  fault = false 
)

Definition at line 91 of file motion_safety_node.cpp.

void MotionSafety::watchdogCallback ( const ros::TimerEvent ) [protected]

Definition at line 132 of file motion_safety_node.cpp.


Member Data Documentation

Definition at line 142 of file motion_safety.h.

Definition at line 137 of file motion_safety.h.

Definition at line 137 of file motion_safety.h.

Definition at line 130 of file motion_safety.h.

Definition at line 140 of file motion_safety.h.

Definition at line 135 of file motion_safety.h.

Definition at line 105 of file motion_safety.h.

grizzly_msgs::RawStatusConstPtr MotionSafety::last_mcu_status_ [protected]

Definition at line 120 of file motion_safety.h.

Definition at line 106 of file motion_safety.h.

double MotionSafety::max_accel_ [protected]

Definition at line 146 of file motion_safety.h.

Definition at line 136 of file motion_safety.h.

Definition at line 136 of file motion_safety.h.

Definition at line 141 of file motion_safety.h.

Definition at line 93 of file motion_safety.h.

Definition at line 126 of file motion_safety.h.

Definition at line 127 of file motion_safety.h.

Definition at line 123 of file motion_safety.h.

double MotionSafety::radius_ [protected]

Definition at line 145 of file motion_safety.h.

std::string MotionSafety::reason_ [protected]

Definition at line 101 of file motion_safety.h.

Definition at line 109 of file motion_safety.h.

Definition at line 100 of file motion_safety.h.

Definition at line 119 of file motion_safety.h.

Definition at line 119 of file motion_safety.h.

Definition at line 119 of file motion_safety.h.

Definition at line 113 of file motion_safety.h.

Definition at line 99 of file motion_safety.h.

double MotionSafety::width_ [protected]

Definition at line 144 of file motion_safety.h.


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


grizzly_motion
Author(s):
autogenerated on Thu Jun 6 2019 21:44:03