#include <mrp2_hardware.h>
|
void | callback (mrp2_hardware::ParametersConfig &config, uint32_t level) |
|
void | estop_clear_callback (const std_msgs::Empty::ConstPtr &msg) |
|
ros::Duration | getPeriod () const |
|
ros::Time | getTime () const |
|
| MRP2HW () |
|
void | positions_reset_callback (const std_msgs::Empty::ConstPtr &msg) |
|
void | read () |
|
bool | start_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
|
bool | stop_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
|
void | write () |
|
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
|
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
|
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
virtual bool | init (ros::NodeHandle &, ros::NodeHandle &) |
|
virtual bool | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
virtual void | read (const ros::Time &, const ros::Duration &) |
|
virtual void | read (const ros::Time &, const ros::Duration &) |
|
virtual SwitchState | switchResult (const ControllerInfo &) const |
|
virtual SwitchState | switchResult () const |
|
virtual void | write (const ros::Time &, const ros::Duration &) |
|
virtual void | write (const ros::Time &, const ros::Duration &) |
|
virtual | ~RobotHW ()=default |
|
T * | get () |
|
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
|
std::vector< std::string > | getNames () const |
|
void | registerInterface (T *iface) |
|
void | registerInterfaceManager (InterfaceManager *iface_man) |
|
|
double | _ftod (float fValue) |
|
Definition at line 36 of file mrp2_hardware.h.
◆ MRP2HW()
◆ _ftod()
double MRP2HW::_ftod |
( |
float |
fValue | ) |
|
|
inlineprivate |
◆ callback()
void MRP2HW::callback |
( |
mrp2_hardware::ParametersConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
inline |
◆ estop_clear_callback()
void MRP2HW::estop_clear_callback |
( |
const std_msgs::Empty::ConstPtr & |
msg | ) |
|
|
inline |
◆ getPeriod()
◆ getTime()
◆ positions_reset_callback()
void MRP2HW::positions_reset_callback |
( |
const std_msgs::Empty::ConstPtr & |
msg | ) |
|
|
inline |
◆ read()
◆ start_callback()
bool MRP2HW::start_callback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
inline |
◆ stop_callback()
bool MRP2HW::stop_callback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
inline |
◆ write()
◆ aux_lights_pub
◆ batt_high_pub
◆ batt_low_pub
◆ bumper_states
std::vector<int> MRP2HW::bumper_states |
|
private |
◆ bumpers_pub
◆ cmd_
◆ connect_mutex_
boost::mutex MRP2HW::connect_mutex_ |
|
private |
◆ controller_pub
◆ current_time
◆ diags
std::vector<int> MRP2HW::diags |
|
private |
◆ dynamic_reconfigure_mutex_
boost::recursive_mutex MRP2HW::dynamic_reconfigure_mutex_ |
|
private |
◆ eff_
◆ estop_btn_pub
◆ estop_clear_sub
◆ estop_pub
◆ estop_release
bool MRP2HW::estop_release |
◆ estop_state
dynamic_reconfigure::Server<mrp2_hardware::ParametersConfig>::CallbackType MRP2HW::f |
|
private |
◆ imu_sens_interface_
◆ init_config
mrp2_hardware::ParametersConfig MRP2HW::init_config |
|
private |
◆ jnt_state_interface_
◆ jnt_vel_interface_
◆ last_time
◆ motor_stall_l_pub
◆ motor_stall_r_pub
◆ nh_
◆ pos_
◆ pos_left
◆ pos_reset_sub
◆ pos_right
◆ publish_feed
bool MRP2HW::publish_feed |
|
private |
◆ publish_pos
◆ publish_ref
◆ robot_serial
◆ running_
◆ sep_cmd_vel_pub
◆ server
dynamic_reconfigure::Server<mrp2_hardware::ParametersConfig> MRP2HW::server |
|
private |
◆ speeds
std::vector<int> MRP2HW::speeds |
|
private |
◆ start_srv_
◆ stop_srv_
◆ sym_tuning
◆ vel_
The documentation for this class was generated from the following file: