Go to the documentation of this file. 1 #ifndef EMC_COMMUNICATION_H_
2 #define EMC_COMMUNICATION_H_
9 #include <ros/publisher.h>
10 #include <ros/subscriber.h>
11 #include <ros/callback_queue.h>
12 #include <tf2_ros/transform_broadcaster.h>
13 #include <sensor_msgs/JointState.h>
14 #include <nav_msgs/MapMetaData.h>
16 #include <std_msgs/Bool.h>
17 #include <sensor_msgs/LaserScan.h>
18 #include <geometry_msgs/PoseArray.h>
19 #include <visualization_msgs/Marker.h>
20 #include <nav_msgs/Odometry.h>
21 #include <geometry_msgs/PoseStamped.h>
53 void sendMarker(visualization_msgs::Marker marker);
99 void laserCallback(
const sensor_msgs::LaserScanConstPtr& msg);
109 void poseCallback(
const geometry_msgs::PoseStampedConstPtr& msg);
119 void odomCallback(
const nav_msgs::OdometryConstPtr& msg);
std_msgs::BoolConstPtr bumper_f_msg_
sensor_msgs::LaserScanConstPtr laser_msg_
ros::Publisher pub_open_door_
void poseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
ros::CallbackQueue odom_cb_queue_
void sendPoseEstimate(const geometry_msgs::Transform &pose)
ros::Subscriber sub_bumper_f_
ros::CallbackQueue bumper_f_cb_queue_
std_msgs::BoolConstPtr bumper_b_msg_
bool readPoseData(PoseData &pose)
bool readOdometryData(OdometryData &odom)
ros::Publisher pub_speak_
nav_msgs::OdometryConstPtr odom_msg_
ros::CallbackQueue bumper_b_cb_queue_
void localization_viz_send_laser_scan(double angle_min, double angle_max, double angle_inc, int subsample, std::vector< float > prediction)
ros::Subscriber sub_odom_
geometry_msgs::PoseStampedConstPtr pose_msg_
void localization_viz_send_particles(int N, std::vector< std::vector< double >> particle_poses, double mapOrientation)
std::unique_ptr< tf2_ros::TransformBroadcaster > pub_tf2
ros::Publisher pub_base_ref_
ros::CallbackQueue laser_cb_queue_
ros::Publisher localization_visualization_pub_particle_
ros::Subscriber sub_bumper_b_
void odomCallback(const nav_msgs::OdometryConstPtr &msg)
void sendBaseVelocity(double vx, double vy, double va)
ros::Subscriber sub_pose_
void speak(const std::string &text)
ros::Publisher pub_marker_
void localization_viz_send_pose(std::vector< double > pose, double mapOrientation)
void sendMarker(visualization_msgs::Marker marker)
void sendOpendoorRequest()
void bumperbCallback(const std_msgs::BoolConstPtr &msg)
ros::Publisher localization_visualization_pub_laser_msg_
bool readFrontBumperData(BumperData &bumper)
ros::CallbackQueue pose_cb_queue_
ros::Subscriber sub_laser_
ros::Publisher localization_visualization_pub_pose_
void laserCallback(const sensor_msgs::LaserScanConstPtr &msg)
void play(const std::string &file)
bool readBackBumperData(BumperData &bumper)
Communication(std::string robot_name="pyro")
bool readLaserData(LaserData &scan)
std::string robot_frame_name
void bumperfCallback(const std_msgs::BoolConstPtr &msg)