Go to the documentation of this file. 1 #ifndef EMC_SYSTEM_IO_H_
2 #define EMC_SYSTEM_IO_H_
159 bool sendPoseEstimate(
double px,
double py,
double pz,
double rx,
double ry,
double rz,
double rw);
171 bool sendPoseEstimate(
double px,
double py,
double pz,
double rr,
double rp,
double ry);
bool readLaserData(LaserData &scan)
Receive new laser data if available.
void localization_viz_send_laser_scan(double angle_min, double angle_max, double angle_inc, int subsample, std::vector< float > prediction)
IO(Communication *comm=nullptr)
bool readOdometryData(OdometryData &odom)
Receive new odometrydata if available.
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.
bool resetOdometry()
Set the current position as (0,0,0)
void sendBaseReference(double vx, double vy, double va)
Send a command velocity to the robot.
bool readFrontBumperData(BumperData &bumper)
Receive new BumperData from the front bumper.
void localization_viz_send_particles(int N, std::vector< std::vector< double >> particle_poses, double mapOrientation)
bool ok()
Check connection to the robot.
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 ....
void localization_viz_send_pose(std::vector< double > pose, double mapOrientation)
void sendOpendoorRequest()
Broadcast a request to open nearby doors. Works in simulator only.
bool readPoseData(PoseData &pose)
Receive new pose data if available.
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...
bool readBackBumperData(BumperData &bumper)
Receive new BumperData from the rear bumper.
void speak(const std::string &text)
Make the robot speak the input text. This function is non-blocking.