emc_system
communication.h
Go to the documentation of this file.
1 #ifndef EMC_COMMUNICATION_H_
2 #define EMC_COMMUNICATION_H_
3 
4 #include "emc/data.h"
5 #include "emc/odom.h"
6 #include "emc/pose.h"
7 #include "emc/bumper.h"
8 
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>
15 
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>
22 #include <string>
23 #include <memory>
24 
25 namespace emc
26 {
27 
29 {
30 
31 public:
32 
33  Communication(std::string robot_name="pyro");
34 
36 
37  void init();
38 
39  bool readLaserData(LaserData& scan);
40 
41  bool readPoseData(PoseData& pose);
42 
43  bool readOdometryData(OdometryData& odom);
44 
45  bool readFrontBumperData(BumperData& bumper);
46  bool readBackBumperData(BumperData& bumper);
47 
48 
49  void sendBaseVelocity(double vx, double vy, double va);
50 
51  void sendOpendoorRequest();
52 
53  void sendMarker(visualization_msgs::Marker marker);
54 
55  void speak(const std::string& text);
56 
57  void play(const std::string& file);
58 
59  // Postion data
60  void sendPoseEstimate(const geometry_msgs::Transform& pose);
61 
62  // publishing functions used to visualize information in the localization exercises (particle filter):
63  void localization_viz_send_laser_scan(double angle_min, double angle_max, double angle_inc, int subsample, std::vector<float> prediction);
64  void localization_viz_send_particles(int N, std::vector<std::vector<double>> particle_poses, double mapOrientation);
65  void localization_viz_send_pose(std::vector<double> pose, double mapOrientation);
66 
67 private:
68 
69  // Base velocity reference
70 
71  ros::Publisher pub_base_ref_;
72 
73  ros::Publisher pub_open_door_;
74 
75  ros::Publisher pub_speak_;
76 
77  ros::Publisher pub_play_;
78 
79  ros::Publisher pub_marker_;
80 
81  // publishers used to visualize information in the localization exercises (particle filter):
85 
86  // Position data
87 
88  std::unique_ptr<tf2_ros::TransformBroadcaster> pub_tf2; //has to be defined after ros::init(), which is called in the constructor
89 
90 
91  // Laser data
92 
93  ros::CallbackQueue laser_cb_queue_;
94 
95  ros::Subscriber sub_laser_;
96 
97  sensor_msgs::LaserScanConstPtr laser_msg_;
98 
99  void laserCallback(const sensor_msgs::LaserScanConstPtr& msg);
100 
101  // Pose data
102 
103  ros::CallbackQueue pose_cb_queue_;
104 
105  ros::Subscriber sub_pose_;
106 
107  geometry_msgs::PoseStampedConstPtr pose_msg_;
108 
109  void poseCallback(const geometry_msgs::PoseStampedConstPtr& msg);
110 
111  // Odometry data
112 
113  ros::CallbackQueue odom_cb_queue_;
114 
115  ros::Subscriber sub_odom_;
116 
117  nav_msgs::OdometryConstPtr odom_msg_;
118 
119  void odomCallback(const nav_msgs::OdometryConstPtr& msg);
120 
121  // Bumper data
122 
123  ros::CallbackQueue bumper_f_cb_queue_;
124  ros::CallbackQueue bumper_b_cb_queue_;
125 
126  ros::Subscriber sub_bumper_f_;
127  ros::Subscriber sub_bumper_b_;
128 
129  std_msgs::BoolConstPtr bumper_f_msg_;
130  std_msgs::BoolConstPtr bumper_b_msg_;
131 
132  void bumperfCallback(const std_msgs::BoolConstPtr& msg);
133  void bumperbCallback(const std_msgs::BoolConstPtr& msg);
134 
135  // pose publishing
137 };
138 
139 } // end namespace emc
140 
141 #endif
emc::Communication::~Communication
~Communication()
Definition: communication.cpp:75
emc::Communication::pub_play_
ros::Publisher pub_play_
Definition: communication.h:77
std::string
emc::Communication::bumper_f_msg_
std_msgs::BoolConstPtr bumper_f_msg_
Definition: communication.h:129
pose.h
emc::Communication::laser_msg_
sensor_msgs::LaserScanConstPtr laser_msg_
Definition: communication.h:97
emc::Communication::pub_open_door_
ros::Publisher pub_open_door_
Definition: communication.h:73
emc::Communication::poseCallback
void poseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
Definition: communication.cpp:264
std::vector< float >
emc::Communication::odom_cb_queue_
ros::CallbackQueue odom_cb_queue_
Definition: communication.h:113
emc::Communication::sendPoseEstimate
void sendPoseEstimate(const geometry_msgs::Transform &pose)
Definition: communication.cpp:238
emc::PoseData
Definition: pose.h:9
emc::Communication::sub_bumper_f_
ros::Subscriber sub_bumper_f_
Definition: communication.h:126
emc::Communication::bumper_f_cb_queue_
ros::CallbackQueue bumper_f_cb_queue_
Definition: communication.h:123
emc::Communication::bumper_b_msg_
std_msgs::BoolConstPtr bumper_b_msg_
Definition: communication.h:130
emc::Communication::readPoseData
bool readPoseData(PoseData &pose)
Definition: communication.cpp:109
emc::Communication::readOdometryData
bool readOdometryData(OdometryData &odom)
Definition: communication.cpp:145
emc::Communication::pub_speak_
ros::Publisher pub_speak_
Definition: communication.h:75
emc::Communication::odom_msg_
nav_msgs::OdometryConstPtr odom_msg_
Definition: communication.h:117
emc::Communication::init
void init()
Definition: communication.cpp:82
emc::OdometryData
Definition: odom.h:9
emc::Communication::bumper_b_cb_queue_
ros::CallbackQueue bumper_b_cb_queue_
Definition: communication.h:124
emc::Communication::localization_viz_send_laser_scan
void localization_viz_send_laser_scan(double angle_min, double angle_max, double angle_inc, int subsample, std::vector< float > prediction)
Definition: communication.cpp:293
emc::Communication::sub_odom_
ros::Subscriber sub_odom_
Definition: communication.h:115
emc::Communication::pose_msg_
geometry_msgs::PoseStampedConstPtr pose_msg_
Definition: communication.h:107
emc::LaserData
Definition: data.h:14
emc::Communication::localization_viz_send_particles
void localization_viz_send_particles(int N, std::vector< std::vector< double >> particle_poses, double mapOrientation)
Definition: communication.cpp:313
emc::Communication::pub_tf2
std::unique_ptr< tf2_ros::TransformBroadcaster > pub_tf2
Definition: communication.h:88
emc::Communication::pub_base_ref_
ros::Publisher pub_base_ref_
Definition: communication.h:71
emc::Communication::laser_cb_queue_
ros::CallbackQueue laser_cb_queue_
Definition: communication.h:93
emc::Communication::localization_visualization_pub_particle_
ros::Publisher localization_visualization_pub_particle_
Definition: communication.h:83
emc::Communication::sub_bumper_b_
ros::Subscriber sub_bumper_b_
Definition: communication.h:127
emc::Communication::odomCallback
void odomCallback(const nav_msgs::OdometryConstPtr &msg)
Definition: communication.cpp:271
memory
emc::Communication::sendBaseVelocity
void sendBaseVelocity(double vx, double vy, double va)
Definition: communication.cpp:197
emc::Communication::sub_pose_
ros::Subscriber sub_pose_
Definition: communication.h:105
emc::Communication::speak
void speak(const std::string &text)
Definition: communication.cpp:224
emc::Communication
Definition: communication.h:28
emc::Communication::pub_marker_
ros::Publisher pub_marker_
Definition: communication.h:79
emc::Communication::localization_viz_send_pose
void localization_viz_send_pose(std::vector< double > pose, double mapOrientation)
Definition: communication.cpp:342
emc::Communication::sendMarker
void sendMarker(visualization_msgs::Marker marker)
Definition: communication.cpp:217
emc::Communication::sendOpendoorRequest
void sendOpendoorRequest()
Definition: communication.cpp:209
data.h
emc::Communication::bumperbCallback
void bumperbCallback(const std_msgs::BoolConstPtr &msg)
Definition: communication.cpp:285
emc::Communication::localization_visualization_pub_laser_msg_
ros::Publisher localization_visualization_pub_laser_msg_
Definition: communication.h:82
emc
Definition: bumper.h:4
emc::Communication::readFrontBumperData
bool readFrontBumperData(BumperData &bumper)
Definition: communication.cpp:167
emc::Communication::pose_cb_queue_
ros::CallbackQueue pose_cb_queue_
Definition: communication.h:103
emc::Communication::sub_laser_
ros::Subscriber sub_laser_
Definition: communication.h:95
emc::Communication::localization_visualization_pub_pose_
ros::Publisher localization_visualization_pub_pose_
Definition: communication.h:84
emc::Communication::laserCallback
void laserCallback(const sensor_msgs::LaserScanConstPtr &msg)
Definition: communication.cpp:257
emc::Communication::play
void play(const std::string &file)
Definition: communication.cpp:231
std::unique_ptr< tf2_ros::TransformBroadcaster >
emc::Communication::readBackBumperData
bool readBackBumperData(BumperData &bumper)
Definition: communication.cpp:182
emc::Communication::Communication
Communication(std::string robot_name="pyro")
Definition: communication.cpp:20
emc::Communication::readLaserData
bool readLaserData(LaserData &scan)
Definition: communication.cpp:88
emc::Communication::robot_frame_name
std::string robot_frame_name
Definition: communication.h:136
bumper.h
emc::BumperData
Definition: bumper.h:9
emc::Communication::bumperfCallback
void bumperfCallback(const std_msgs::BoolConstPtr &msg)
Definition: communication.cpp:278
odom.h
string