Go to the documentation of this file.
28 #ifndef CREATE_DRIVER_CREATE_DRIVER_H
29 #define CREATE_DRIVER_CREATE_DRIVER_H
30 #include "create_msgs/ChargingState.h"
31 #include "create_msgs/Mode.h"
32 #include "create_msgs/Bumper.h"
33 #include "create_msgs/DefineSong.h"
34 #include "create_msgs/PlaySong.h"
35 #include "create_msgs/MotorSetpoint.h"
40 #include <geometry_msgs/TransformStamped.h>
41 #include <geometry_msgs/Twist.h>
42 #include <nav_msgs/Odometry.h>
44 #include <sensor_msgs/JointState.h>
45 #include <std_msgs/Bool.h>
46 #include <std_msgs/Empty.h>
47 #include <std_msgs/Float32.h>
48 #include <std_msgs/Int16.h>
49 #include <std_msgs/UInt16.h>
50 #include <std_msgs/UInt8MultiArray.h>
55 static const double COVARIANCE[36] = {1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5,
56 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5,
57 0.0, 0.0, 1e-5, 0.0, 0.0, 0.0,
58 0.0, 0.0, 0.0, 1e-5, 0.0, 0.0,
59 0.0, 0.0, 0.0, 0.0, 1e-5, 0.0,
60 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5};
143 void sideBrushMotor(
const create_msgs::MotorSetpointConstPtr& msg);
144 void mainBrushMotor(
const create_msgs::MotorSetpointConstPtr& msg);
169 #endif // CREATE_DRIVER_CREATE_DRIVER_H
ros::Publisher charge_ratio_pub_
ros::Publisher voltage_pub_
void debrisLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::Publisher dock_btn_pub_
ros::Publisher capacity_pub_
void updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
ros::Publisher temperature_pub_
std_msgs::UInt16 uint16_msg_
ros::Subscriber set_ascii_sub_
void publishButtonPresses() const
ros::Publisher spot_btn_pub_
void playSongCallback(const create_msgs::PlaySongConstPtr &msg)
void spotLEDCallback(const std_msgs::BoolConstPtr &msg)
void checkLEDCallback(const std_msgs::BoolConstPtr &msg)
tf2_ros::TransformBroadcaster tf_broadcaster_
diagnostic_updater::Updater diagnostics_
ros::Subscriber dock_led_sub_
ros::Publisher wheeldrop_pub_
void updateBatteryDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Subscriber play_song_sub_
void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void defineSongCallback(const create_msgs::DefineSongConstPtr &msg)
ros::Subscriber dock_sub_
ros::Subscriber vacuum_motor_sub_
std_msgs::Empty empty_msg_
create_msgs::Mode mode_msg_
void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
ros::Subscriber spot_led_sub_
create_msgs::ChargingState charging_state_msg_
sensor_msgs::JointState joint_state_msg_
ros::Subscriber main_brush_motor_sub_
void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Time last_cmd_vel_time_
ros::Publisher min_btn_pub_
void undockCallback(const std_msgs::EmptyConstPtr &msg)
create_msgs::Bumper bumper_msg_
nav_msgs::Odometry odom_msg_
void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void publishBatteryInfo()
void dockLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::Subscriber check_led_sub_
ros::Publisher hour_btn_pub_
ros::Subscriber debris_led_sub_
std_msgs::Float32 float32_msg_
static const double COVARIANCE[36]
ros::Subscriber power_led_sub_
void sideBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
ros::Subscriber side_brush_motor_sub_
ros::Publisher charge_pub_
ros::Subscriber undock_sub_
ros::Subscriber cmd_vel_sub_
void vacuumBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
ros::Publisher clean_btn_pub_
ros::Publisher bumper_pub_
ros::Publisher omni_char_pub_
std_msgs::Int16 int16_msg_
ros::Publisher charging_state_pub_
CreateDriver(ros::NodeHandle &nh)
void dockCallback(const std_msgs::EmptyConstPtr &msg)
ros::Publisher wheel_joint_pub_
ros::Subscriber define_song_sub_
void mainBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
ros::Publisher day_btn_pub_
create::RobotModel model_
geometry_msgs::TransformStamped tf_odom_
ros::Publisher current_pub_
create_driver
Author(s): Jacob Perron
autogenerated on Wed May 24 2023 02:19:10