emc_system
io.h
Go to the documentation of this file.
1 #ifndef EMC_SYSTEM_IO_H_
2 #define EMC_SYSTEM_IO_H_
3 
4 #include <array>
5 #include <vector>
6 #include <string>
7 
8 #include "emc/data.h"
9 #include "emc/odom.h"
10 #include "emc/pose.h"
11 #include "emc/bumper.h"
12 
13 namespace emc
14 {
15 
16 class Communication;
17 
18 class IO
19 {
20 
21 public:
22 
23  IO(Communication* comm = nullptr);
24  IO(std::string robot_name);
25 
26  ~IO();
27 
35  bool readLaserData(LaserData& scan);
36 
44  bool readPoseData(PoseData& pose);
45 
54  bool readOdometryData(OdometryData& odom);
55 
61  bool resetOdometry();
62 
70  bool readFrontBumperData(BumperData& bumper);
71 
79  bool readBackBumperData(BumperData& bumper);
80 
88  void sendBaseReference(double vx, double vy, double va);
89 
94  void sendOpendoorRequest();
95 
102  bool ok();
103 
109  void speak(const std::string& text);
110 
116  void play(const std::string& file);
117 
129  bool sendPath(std::vector<std::vector<double>> path, std::array<double, 3> color = {0.0, 0.0, 0.0}, double width = 0.02, int id = 0);
130 
131 
139  bool sendPoseEstimate(double x, double y, double yaw);
140 
141  // publishers used to visualize information in the localization exercises (particle filter):
142  void localization_viz_send_laser_scan(double angle_min, double angle_max, double angle_inc, int subsample, std::vector<float> prediction);
143  void localization_viz_send_particles(int N, std::vector<std::vector<double>> particle_poses, double mapOrientation);
144  void localization_viz_send_pose(std::vector<double> pose, double mapOrientation);
145 
146 private:
147 
159  bool sendPoseEstimate(double px, double py, double pz, double rx, double ry, double rz, double rw); //use quaternion
160 
171  bool sendPoseEstimate(double px, double py, double pz, double rr, double rp, double ry); //use roll pitch yaw
172 
173  // odometry memory
175  bool odom_set_ = false; // wether odom has been set at least once.
176 
178 
179 };
180 
181 } // end namespace emc
182 
183 #endif
emc::IO::readLaserData
bool readLaserData(LaserData &scan)
Receive new laser data if available.
Definition: io.cpp:34
std::string
pose.h
emc::IO::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: io.cpp:199
emc::IO::~IO
~IO()
Definition: io.cpp:28
emc::IO::IO
IO(Communication *comm=nullptr)
Definition: io.cpp:18
vector
emc::IO::readOdometryData
bool readOdometryData(OdometryData &odom)
Receive new odometrydata if available.
Definition: io.cpp:44
emc::IO::odom_set_
bool odom_set_
Definition: io.h:175
emc::PoseData
Definition: pose.h:9
emc::IO::sendPath
bool sendPath(std::vector< std::vector< double >> path, std::array< double, 3 > color={0.0, 0.0, 0.0}, double width=0.02, int id=0)
Send a path to be drawn in rviz.
Definition: io.cpp:124
emc::IO::resetOdometry
bool resetOdometry()
Set the current position as (0,0,0)
Definition: io.cpp:69
emc::OdometryData
Definition: odom.h:9
emc::LaserData
Definition: data.h:14
array
emc::IO
Definition: io.h:18
emc::IO::sendBaseReference
void sendBaseReference(double vx, double vy, double va)
Send a command velocity to the robot.
Definition: io.cpp:89
emc::IO::readFrontBumperData
bool readFrontBumperData(BumperData &bumper)
Receive new BumperData from the front bumper.
Definition: io.cpp:79
emc::Communication
Definition: communication.h:28
emc::IO::prev_odom_
OdometryData prev_odom_
Definition: io.h:174
emc::IO::localization_viz_send_particles
void localization_viz_send_particles(int N, std::vector< std::vector< double >> particle_poses, double mapOrientation)
Definition: io.cpp:205
emc::IO::ok
bool ok()
Check connection to the robot.
Definition: io.cpp:119
data.h
emc::IO::play
void play(const std::string &file)
Play a sound file out loud. The file must be placed in the ~/MRC_audio folder and must be of ....
Definition: io.cpp:114
emc::IO::localization_viz_send_pose
void localization_viz_send_pose(std::vector< double > pose, double mapOrientation)
Definition: io.cpp:211
emc
Definition: bumper.h:4
emc::IO::comm_
Communication * comm_
Definition: io.h:177
emc::IO::sendOpendoorRequest
void sendOpendoorRequest()
Broadcast a request to open nearby doors. Works in simulator only.
Definition: io.cpp:94
emc::IO::readPoseData
bool readPoseData(PoseData &pose)
Receive new pose data if available.
Definition: io.cpp:39
emc::IO::sendPoseEstimate
bool sendPoseEstimate(double x, double y, double yaw)
Send an estimate of the current robot pose to be shown in rviz, relative to the centre of the map (sa...
Definition: io.cpp:191
emc::IO::readBackBumperData
bool readBackBumperData(BumperData &bumper)
Receive new BumperData from the rear bumper.
Definition: io.cpp:84
bumper.h
emc::BumperData
Definition: bumper.h:9
emc::IO::speak
void speak(const std::string &text)
Make the robot speak the input text. This function is non-blocking.
Definition: io.cpp:104
odom.h
string