-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathRosbotClass.h
48 lines (43 loc) · 1.08 KB
/
RosbotClass.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
#ifndef ROSBOT_CLASS_H
#define ROSBOT_CLASS_H
#include "geometry_msgs/Twist.h"
#include "nav_msgs/Odometry.h"
#include "sensor_msgs/LaserScan.h"
#include <list>
#include <ros/ros.h>
#include <string>
using namespace std;
class RosbotClass {
private:
// Communicate with nodes
ros::NodeHandle n;
// Laser data
ros::Subscriber laser_sub;
std::vector<float> laser_range;
std::string laser_topic;
// Velocity data
ros::Publisher vel_pub;
geometry_msgs::Twist vel_msg;
std::string vel_topic;
// Odometry data
ros::Subscriber odom_sub;
std::string odom_topic;
float x_pos;
float y_pos;
float z_pos;
void laser_callback(const sensor_msgs::LaserScan::ConstPtr &laser_msg);
void odom_callback(const nav_msgs::Odometry::ConstPtr &odom_msg);
public:
RosbotClass();
void move();
void move_forward(int n_secs);
void move_backwards(int n_secs);
void turn(string clock, int n_secs);
void stop_moving();
float get_position(int param);
std::list<float> get_position_full();
double get_time();
float get_laser(int index);
float *get_laser_full();
};
#endif