Fixed the limited buffer size bug in inmsgs and changed to y formation
This commit is contained in:
parent
fff1c3398d
commit
c41bb81763
|
@ -15,7 +15,7 @@ GOTO_MAXDIST = 150 # m.
|
|||
GOTODIST_TOL = 1.0 # m.
|
||||
GOTOANG_TOL = 0.1 # rad.
|
||||
path_it = 0
|
||||
graphid = 0
|
||||
graphid = 3
|
||||
pic_time = 0
|
||||
g_it = 0
|
||||
|
||||
|
|
|
@ -52,6 +52,7 @@ typedef enum {
|
|||
#define COM_DELAY 100000000 // in nano seconds i.e 100 ms
|
||||
#define TIME_SYNC_JUMP_THR 500000000
|
||||
#define MOVING_AVERAGE_ALPHA 0.1
|
||||
#define MAX_NUMBER_OF_ROBOTS 10
|
||||
|
||||
#define TIMEOUT 60
|
||||
#define BUZZRATE 10
|
||||
|
|
|
@ -392,12 +392,12 @@ void roscontroller::Initialize_pub_sub(ros::NodeHandle& n_c)
|
|||
|
||||
Subscribe(n_c);
|
||||
|
||||
payload_sub = n_c.subscribe(in_payload, 5, &roscontroller::payload_obt, this);
|
||||
payload_sub = n_c.subscribe(in_payload, MAX_NUMBER_OF_ROBOTS, &roscontroller::payload_obt, this);
|
||||
|
||||
// publishers
|
||||
payload_pub = n_c.advertise<mavros_msgs::Mavlink>(out_payload, 5);
|
||||
MPpayload_pub = n_c.advertise<mavros_msgs::Mavlink>("fleet_status", 5);
|
||||
neigh_pos_pub = n_c.advertise<rosbuzz::neigh_pos>("neighbours_pos", 5);
|
||||
neigh_pos_pub = n_c.advertise<rosbuzz::neigh_pos>("neighbours_pos", MAX_NUMBER_OF_ROBOTS);
|
||||
uavstate_pub = n_c.advertise<std_msgs::String>("uavstate", 5);
|
||||
grid_pub = n_c.advertise<nav_msgs::OccupancyGrid>("grid", 5);
|
||||
localsetpoint_nonraw_pub = n_c.advertise<geometry_msgs::PoseStamped>(setpoint_name, 5);
|
||||
|
|
Loading…
Reference in New Issue