beautified and style fixes
This commit is contained in:
parent
5f83aa60f6
commit
fbb0f108b1
|
@ -36,7 +36,6 @@
|
|||
#include <stdio.h>
|
||||
#include <algorithm>
|
||||
|
||||
|
||||
#ifndef NULL
|
||||
#define NULL 0
|
||||
#endif
|
||||
|
@ -45,31 +44,32 @@
|
|||
#define le 0
|
||||
#define re 1
|
||||
|
||||
|
||||
|
||||
struct Freenode
|
||||
{
|
||||
struct Freenode *nextfree;
|
||||
struct Freenode* nextfree;
|
||||
};
|
||||
|
||||
struct FreeNodeArrayList
|
||||
{
|
||||
struct Freenode* memory;
|
||||
struct FreeNodeArrayList* next;
|
||||
|
||||
};
|
||||
|
||||
struct Freelist
|
||||
{
|
||||
struct Freenode *head;
|
||||
struct Freenode* head;
|
||||
int nodesize;
|
||||
};
|
||||
|
||||
struct Point
|
||||
{
|
||||
float x,y;
|
||||
Point(): x( 0.0 ), y( 0.0 ) { }
|
||||
Point( float x, float y ): x( x ), y( y ) { }
|
||||
float x, y;
|
||||
Point() : x(0.0), y(0.0)
|
||||
{
|
||||
}
|
||||
Point(float x, float y) : x(x), y(y)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
// structure used both for sites and for vertices
|
||||
|
@ -80,126 +80,114 @@ struct Site
|
|||
int refcnt;
|
||||
};
|
||||
|
||||
|
||||
|
||||
struct Edge
|
||||
{
|
||||
float a,b,c;
|
||||
struct Site *ep[2];
|
||||
struct Site *reg[2];
|
||||
float a, b, c;
|
||||
struct Site* ep[2];
|
||||
struct Site* reg[2];
|
||||
int edgenbr;
|
||||
int sites[2];
|
||||
|
||||
};
|
||||
|
||||
struct GraphEdge
|
||||
{
|
||||
float x1,y1,x2,y2;
|
||||
float x1, y1, x2, y2;
|
||||
int sites[2];
|
||||
struct GraphEdge* next;
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
struct Halfedge
|
||||
{
|
||||
struct Halfedge *ELleft, *ELright;
|
||||
struct Edge *ELedge;
|
||||
struct Edge* ELedge;
|
||||
int ELrefcnt;
|
||||
char ELpm;
|
||||
struct Site *vertex;
|
||||
struct Site* vertex;
|
||||
float ystar;
|
||||
struct Halfedge *PQnext;
|
||||
struct Halfedge* PQnext;
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
class VoronoiDiagramGenerator
|
||||
{
|
||||
public:
|
||||
VoronoiDiagramGenerator();
|
||||
~VoronoiDiagramGenerator();
|
||||
|
||||
bool generateVoronoi(float *xValues, float *yValues, int numPoints, float minX, float maxX, float minY, float maxY, float minDist=0);
|
||||
bool generateVoronoi(float* xValues, float* yValues, int numPoints, float minX, float maxX, float minY, float maxY,
|
||||
float minDist = 0);
|
||||
|
||||
void resetIterator()
|
||||
{
|
||||
iteratorEdges = allEdges;
|
||||
}
|
||||
|
||||
bool getNext(float& x1, float& y1, float& x2, float& y2, int *s)
|
||||
bool getNext(float& x1, float& y1, float& x2, float& y2, int* s)
|
||||
{
|
||||
if(iteratorEdges == 0)
|
||||
if (iteratorEdges == 0)
|
||||
return false;
|
||||
|
||||
x1 = iteratorEdges->x1;
|
||||
x2 = iteratorEdges->x2;
|
||||
y1 = iteratorEdges->y1;
|
||||
y2 = iteratorEdges->y2;
|
||||
std::copy(iteratorEdges->sites, iteratorEdges->sites+2, s);
|
||||
std::copy(iteratorEdges->sites, iteratorEdges->sites + 2, s);
|
||||
|
||||
iteratorEdges = iteratorEdges->next;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
private:
|
||||
void cleanup();
|
||||
void cleanupEdges();
|
||||
char *getfree(struct Freelist *fl);
|
||||
struct Halfedge *PQfind();
|
||||
char* getfree(struct Freelist* fl);
|
||||
struct Halfedge* PQfind();
|
||||
int PQempty();
|
||||
|
||||
|
||||
|
||||
struct Halfedge **ELhash;
|
||||
struct Halfedge** ELhash;
|
||||
struct Halfedge *HEcreate(), *ELleft(), *ELright(), *ELleftbnd();
|
||||
struct Halfedge *HEcreate(struct Edge *e,int pm);
|
||||
|
||||
struct Halfedge* HEcreate(struct Edge* e, int pm);
|
||||
|
||||
struct Point PQ_min();
|
||||
struct Halfedge *PQextractmin();
|
||||
void freeinit(struct Freelist *fl,int size);
|
||||
void makefree(struct Freenode *curr,struct Freelist *fl);
|
||||
struct Halfedge* PQextractmin();
|
||||
void freeinit(struct Freelist* fl, int size);
|
||||
void makefree(struct Freenode* curr, struct Freelist* fl);
|
||||
void geominit();
|
||||
void plotinit();
|
||||
bool voronoi(int triangulate);
|
||||
void ref(struct Site *v);
|
||||
void deref(struct Site *v);
|
||||
void endpoint(struct Edge *e,int lr,struct Site * s);
|
||||
void ref(struct Site* v);
|
||||
void deref(struct Site* v);
|
||||
void endpoint(struct Edge* e, int lr, struct Site* s);
|
||||
|
||||
void ELdelete(struct Halfedge *he);
|
||||
struct Halfedge *ELleftbnd(struct Point *p);
|
||||
struct Halfedge *ELright(struct Halfedge *he);
|
||||
void makevertex(struct Site *v);
|
||||
void out_triple(struct Site *s1, struct Site *s2,struct Site * s3);
|
||||
void ELdelete(struct Halfedge* he);
|
||||
struct Halfedge* ELleftbnd(struct Point* p);
|
||||
struct Halfedge* ELright(struct Halfedge* he);
|
||||
void makevertex(struct Site* v);
|
||||
void out_triple(struct Site* s1, struct Site* s2, struct Site* s3);
|
||||
|
||||
void PQinsert(struct Halfedge *he,struct Site * v, float offset);
|
||||
void PQdelete(struct Halfedge *he);
|
||||
void PQinsert(struct Halfedge* he, struct Site* v, float offset);
|
||||
void PQdelete(struct Halfedge* he);
|
||||
bool ELinitialize();
|
||||
void ELinsert(struct Halfedge *lb, struct Halfedge *newHe);
|
||||
struct Halfedge * ELgethash(int b);
|
||||
struct Halfedge *ELleft(struct Halfedge *he);
|
||||
struct Site *leftreg(struct Halfedge *he);
|
||||
void out_site(struct Site *s);
|
||||
void ELinsert(struct Halfedge* lb, struct Halfedge* newHe);
|
||||
struct Halfedge* ELgethash(int b);
|
||||
struct Halfedge* ELleft(struct Halfedge* he);
|
||||
struct Site* leftreg(struct Halfedge* he);
|
||||
void out_site(struct Site* s);
|
||||
bool PQinitialize();
|
||||
int PQbucket(struct Halfedge *he);
|
||||
void clip_line(struct Edge *e);
|
||||
char *myalloc(unsigned n);
|
||||
int right_of(struct Halfedge *el,struct Point *p);
|
||||
int PQbucket(struct Halfedge* he);
|
||||
void clip_line(struct Edge* e);
|
||||
char* myalloc(unsigned n);
|
||||
int right_of(struct Halfedge* el, struct Point* p);
|
||||
|
||||
struct Site *rightreg(struct Halfedge *he);
|
||||
struct Edge *bisect(struct Site *s1,struct Site *s2);
|
||||
float dist(struct Site *s,struct Site *t);
|
||||
struct Site *intersect(struct Halfedge *el1, struct Halfedge *el2, struct Point *p=0);
|
||||
struct Site* rightreg(struct Halfedge* he);
|
||||
struct Edge* bisect(struct Site* s1, struct Site* s2);
|
||||
float dist(struct Site* s, struct Site* t);
|
||||
struct Site* intersect(struct Halfedge* el1, struct Halfedge* el2, struct Point* p = 0);
|
||||
|
||||
void out_bisector(struct Edge *e);
|
||||
void out_ep(struct Edge *e);
|
||||
void out_vertex(struct Site *v);
|
||||
struct Site *nextone();
|
||||
void out_bisector(struct Edge* e);
|
||||
void out_ep(struct Edge* e);
|
||||
void out_vertex(struct Site* v);
|
||||
struct Site* nextone();
|
||||
|
||||
void pushGraphEdge(float x1, float y1, float x2, float y2, int s[2]);
|
||||
|
||||
|
@ -215,18 +203,18 @@ private:
|
|||
int triangulate, sorted, plot, debug;
|
||||
float xmin, xmax, ymin, ymax, deltax, deltay;
|
||||
|
||||
struct Site *sites;
|
||||
struct Site* sites;
|
||||
int nsites;
|
||||
int siteidx;
|
||||
int sqrt_nsites;
|
||||
int nvertices;
|
||||
struct Freelist sfl;
|
||||
struct Site *bottomsite;
|
||||
struct Site* bottomsite;
|
||||
|
||||
int nedges;
|
||||
struct Freelist efl;
|
||||
int PQhashsize;
|
||||
struct Halfedge *PQhash;
|
||||
struct Halfedge* PQhash;
|
||||
int PQcount;
|
||||
int PQmin;
|
||||
|
||||
|
@ -243,12 +231,8 @@ private:
|
|||
GraphEdge* iteratorEdges;
|
||||
|
||||
float minDistanceBetweenSites;
|
||||
|
||||
};
|
||||
|
||||
int scomp(const void *p1,const void *p2);
|
||||
|
||||
int scomp(const void* p1, const void* p2);
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -23,52 +23,52 @@
|
|||
} while (0)
|
||||
namespace buzz_update
|
||||
{
|
||||
static const uint16_t CODE_REQUEST_PADDING = 250;
|
||||
static const uint16_t MIN_UPDATE_PACKET = 251;
|
||||
static const uint16_t UPDATE_CODE_HEADER_SIZE = 5;
|
||||
static const uint16_t TIMEOUT_FOR_ROLLBACK = 50;
|
||||
/*********************/
|
||||
/* Updater states */
|
||||
/********************/
|
||||
static const uint16_t CODE_REQUEST_PADDING = 250;
|
||||
static const uint16_t MIN_UPDATE_PACKET = 251;
|
||||
static const uint16_t UPDATE_CODE_HEADER_SIZE = 5;
|
||||
static const uint16_t TIMEOUT_FOR_ROLLBACK = 50;
|
||||
/*********************/
|
||||
/* Updater states */
|
||||
/********************/
|
||||
|
||||
typedef enum {
|
||||
typedef enum {
|
||||
CODE_RUNNING = 0, // Code executing
|
||||
CODE_STANDBY, // Standing by for others to update
|
||||
} code_states_e;
|
||||
} code_states_e;
|
||||
|
||||
/*********************/
|
||||
/*Message types */
|
||||
/********************/
|
||||
/*********************/
|
||||
/*Message types */
|
||||
/********************/
|
||||
|
||||
typedef enum {
|
||||
typedef enum {
|
||||
SENT_CODE = 0, // Broadcast code
|
||||
RESEND_CODE, // ReBroadcast request
|
||||
} code_message_e;
|
||||
} code_message_e;
|
||||
|
||||
/*************************/
|
||||
/*Updater message queue */
|
||||
/*************************/
|
||||
/*************************/
|
||||
/*Updater message queue */
|
||||
/*************************/
|
||||
|
||||
struct updater_msgqueue_s
|
||||
{
|
||||
struct updater_msgqueue_s
|
||||
{
|
||||
uint8_t* queue;
|
||||
uint8_t* size;
|
||||
};
|
||||
typedef struct updater_msgqueue_s* updater_msgqueue_t;
|
||||
};
|
||||
typedef struct updater_msgqueue_s* updater_msgqueue_t;
|
||||
|
||||
struct updater_code_s
|
||||
{
|
||||
struct updater_code_s
|
||||
{
|
||||
uint8_t* bcode;
|
||||
uint8_t* bcode_size;
|
||||
};
|
||||
typedef struct updater_code_s* updater_code_t;
|
||||
};
|
||||
typedef struct updater_code_s* updater_code_t;
|
||||
|
||||
/**************************/
|
||||
/*Updater data*/
|
||||
/**************************/
|
||||
/**************************/
|
||||
/*Updater data*/
|
||||
/**************************/
|
||||
|
||||
struct buzz_updater_elem_s
|
||||
{
|
||||
struct buzz_updater_elem_s
|
||||
{
|
||||
/* robot id */
|
||||
// uint16_t robotid;
|
||||
/*current Bytecode content */
|
||||
|
@ -92,80 +92,80 @@ namespace buzz_update
|
|||
/*Current state of the updater one in code_states_e ENUM*/
|
||||
int* mode;
|
||||
uint8_t* update_no;
|
||||
};
|
||||
typedef struct buzz_updater_elem_s* buzz_updater_elem_t;
|
||||
};
|
||||
typedef struct buzz_updater_elem_s* buzz_updater_elem_t;
|
||||
|
||||
/**************************************************************************/
|
||||
/*Updater routine from msg processing to file checks to be called from main*/
|
||||
/**************************************************************************/
|
||||
void update_routine();
|
||||
/**************************************************************************/
|
||||
/*Updater routine from msg processing to file checks to be called from main*/
|
||||
/**************************************************************************/
|
||||
void update_routine();
|
||||
|
||||
/************************************************/
|
||||
/*Initalizes the updater */
|
||||
/************************************************/
|
||||
int init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id);
|
||||
/************************************************/
|
||||
/*Initalizes the updater */
|
||||
/************************************************/
|
||||
int init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id);
|
||||
|
||||
/*********************************************************/
|
||||
/*Appends buffer of given size to in msg queue of updater*/
|
||||
/*********************************************************/
|
||||
/*********************************************************/
|
||||
/*Appends buffer of given size to in msg queue of updater*/
|
||||
/*********************************************************/
|
||||
|
||||
void code_message_inqueue_append(uint8_t* msg, uint16_t size);
|
||||
void code_message_inqueue_append(uint8_t* msg, uint16_t size);
|
||||
|
||||
/*********************************************************/
|
||||
/*Processes messages inside the queue of the updater*/
|
||||
/*********************************************************/
|
||||
/*********************************************************/
|
||||
/*Processes messages inside the queue of the updater*/
|
||||
/*********************************************************/
|
||||
|
||||
void code_message_inqueue_process();
|
||||
void code_message_inqueue_process();
|
||||
|
||||
/*****************************************************/
|
||||
/*Obtains messages from out msgs queue of the updater*/
|
||||
/*******************************************************/
|
||||
uint8_t* getupdater_out_msg();
|
||||
/*****************************************************/
|
||||
/*Obtains messages from out msgs queue of the updater*/
|
||||
/*******************************************************/
|
||||
uint8_t* getupdater_out_msg();
|
||||
|
||||
/******************************************************/
|
||||
/*Obtains out msg queue size*/
|
||||
/*****************************************************/
|
||||
uint8_t* getupdate_out_msg_size();
|
||||
/******************************************************/
|
||||
/*Obtains out msg queue size*/
|
||||
/*****************************************************/
|
||||
uint8_t* getupdate_out_msg_size();
|
||||
|
||||
/**************************************************/
|
||||
/*Destroys the out msg queue*/
|
||||
/*************************************************/
|
||||
void destroy_out_msg_queue();
|
||||
/**************************************************/
|
||||
/*Destroys the out msg queue*/
|
||||
/*************************************************/
|
||||
void destroy_out_msg_queue();
|
||||
|
||||
// buzz_updater_elem_t get_updater();
|
||||
/***************************************************/
|
||||
/*Sets bzz file name*/
|
||||
/***************************************************/
|
||||
void set_bzz_file(const char* in_bzz_file, bool dbg);
|
||||
// buzz_updater_elem_t get_updater();
|
||||
/***************************************************/
|
||||
/*Sets bzz file name*/
|
||||
/***************************************************/
|
||||
void set_bzz_file(const char* in_bzz_file, bool dbg);
|
||||
|
||||
/****************************************************/
|
||||
/*Tests the code from a buffer*/
|
||||
/***************************************************/
|
||||
/****************************************************/
|
||||
/*Tests the code from a buffer*/
|
||||
/***************************************************/
|
||||
|
||||
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size);
|
||||
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size);
|
||||
|
||||
/****************************************************/
|
||||
/*Destroys the updater*/
|
||||
/***************************************************/
|
||||
/****************************************************/
|
||||
/*Destroys the updater*/
|
||||
/***************************************************/
|
||||
|
||||
void destroy_updater();
|
||||
void destroy_updater();
|
||||
|
||||
/****************************************************/
|
||||
/*Checks for updater message*/
|
||||
/***************************************************/
|
||||
/****************************************************/
|
||||
/*Checks for updater message*/
|
||||
/***************************************************/
|
||||
|
||||
int is_msg_present();
|
||||
int is_msg_present();
|
||||
|
||||
/****************************************************/
|
||||
/*Compiles a bzz script to bo and bdbg*/
|
||||
/***************************************************/
|
||||
/****************************************************/
|
||||
/*Compiles a bzz script to bo and bdbg*/
|
||||
/***************************************************/
|
||||
|
||||
int compile_bzz(std::string bzz_file);
|
||||
int compile_bzz(std::string bzz_file);
|
||||
|
||||
/****************************************************/
|
||||
/*Set number of robots in the updater*/
|
||||
/***************************************************/
|
||||
/****************************************************/
|
||||
/*Set number of robots in the updater*/
|
||||
/***************************************************/
|
||||
|
||||
void updates_set_robots(int robots);
|
||||
void updates_set_robots(int robots);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -53,8 +53,12 @@ struct neitime
|
|||
double relative_rate;
|
||||
int age;
|
||||
neitime(uint64_t nht, uint64_t nlt, uint64_t mht, uint64_t mlt, double nr, double mr)
|
||||
: nei_hardware_time(nht), nei_logical_time(nlt), node_hardware_time(mht), node_logical_time(mlt),
|
||||
nei_rate(nr), relative_rate(mr) {};
|
||||
: nei_hardware_time(nht)
|
||||
, nei_logical_time(nlt)
|
||||
, node_hardware_time(mht)
|
||||
, node_logical_time(mlt)
|
||||
, nei_rate(nr)
|
||||
, relative_rate(mr){};
|
||||
neitime()
|
||||
{
|
||||
}
|
||||
|
@ -101,5 +105,4 @@ int get_inmsg_size();
|
|||
std::vector<uint8_t*> get_inmsg_vector();
|
||||
|
||||
std::string get_bvmstate();
|
||||
|
||||
}
|
||||
|
|
|
@ -22,7 +22,7 @@ namespace buzzuav_closures
|
|||
int buzzros_print(buzzvm_t vm);
|
||||
void setWPlist(std::string file);
|
||||
void setVorlog(std::string path);
|
||||
void check_targets_sim(double lat, double lon, double *res);
|
||||
void check_targets_sim(double lat, double lon, double* res);
|
||||
|
||||
/*
|
||||
* closure to move following a vector
|
||||
|
@ -98,7 +98,7 @@ double* getgoto();
|
|||
/*
|
||||
* returns the current grid
|
||||
*/
|
||||
std::map<int, std::map<int,int>> getgrid();
|
||||
std::map<int, std::map<int, int>> getgrid();
|
||||
int voronoi_center(buzzvm_t vm);
|
||||
|
||||
/*
|
||||
|
|
|
@ -107,8 +107,8 @@ private:
|
|||
uint16_t size;
|
||||
uint64_t sent_time;
|
||||
uint64_t received_time;
|
||||
MsgData(int mi, uint16_t ni, uint16_t s, uint64_t st, uint64_t rt):
|
||||
msgid(mi), nid(ni), size(s),sent_time(st), received_time(rt){};
|
||||
MsgData(int mi, uint16_t ni, uint16_t s, uint64_t st, uint64_t rt)
|
||||
: msgid(mi), nid(ni), size(s), sent_time(st), received_time(rt){};
|
||||
MsgData(){};
|
||||
};
|
||||
typedef struct MsgData msg_data;
|
||||
|
|
99
readme.md
99
readme.md
|
@ -1,62 +1,43 @@
|
|||
ROS Implemenation of Buzz
|
||||
ROSBuzz
|
||||
=========================
|
||||
|
||||
What is Buzz?
|
||||
=============
|
||||
|
||||
Buzz is a novel programming language for heterogeneous robots swarms.
|
||||
|
||||
Buzz advocates a compositional approach, by offering primitives to define swarm behaviors both in a bottom-up and in a top-down fashion.
|
||||
|
||||
Bottom-up primitives include robot-wise commands and manipulation of neighborhood data through mapping/reducing/filtering operations.
|
||||
|
||||
Top-down primitives allow for the dynamic management of robot teams, and for sharing information globally across the swarm.
|
||||
|
||||
Self-organization results from the fact that the Buzz run-time platform is purely distributed.
|
||||
|
||||
The language can be extended to add new primitives (thus supporting heterogeneous robot swarms) and can be laid on top of other frameworks, such as ROS.
|
||||
|
||||
More information is available at http://the.swarming.buzz/wiki/doku.php?id=start.
|
||||
|
||||
Description:
|
||||
============
|
||||
|
||||
Rosbuzz package is the ROS version of Buzz. The package contains a node called “rosbuzz_node”, which implements buzz virtual machine (BVM) as a node in ROS.
|
||||
ROSBuzz is a ROS node encompassing Buzz Virtual Machine (BVM) and interfacing with ROS ecosystem for mobile robots. The only node of the package is `rosbuzz_node`. It can be used in simulation-in-the-loop using Gazebo and was tested over many platforms (Clearpath Husky, DJI M100, Intel Aero, 3DR Solos, Pleidis Spiris, etc.). More information about ROSBuzz peripheral nodes is available in [1].
|
||||
|
||||
What is Buzz?
|
||||
=============
|
||||
|
||||
Downloading ROS Package
|
||||
=======================
|
||||
|
||||
$ git clone https://github.com/MISTLab/ROSBuzz.git rosbuzz
|
||||
Buzz is a novel programming language for heterogeneous robots swarms. Buzz advocates a compositional approach, by offering primitives to define swarm behaviors both in a bottom-up and in a top-down fashion. Its official documentation and code are available [Buzz](https://github.com/MISTLab/Buzz).
|
||||
|
||||
Requirements
|
||||
============
|
||||
|
||||
* Buzz :
|
||||
* Buzz:
|
||||
|
||||
You can download the development sources through git:
|
||||
Follow the required steps in [Buzz](https://github.com/MISTLab/ROSBuzz).
|
||||
|
||||
$ git clone https://github.com/MISTLab/Buzz.git buzz
|
||||
* ROS **base** binary distribution (Indigo or higher):
|
||||
|
||||
* ROS binary distribution (Indigo or higher) with catkin (could be used with older versions of ROS with catkin but not tested)
|
||||
Follow the required steps in [ROS Kinetic](https://wiki.ros.org/kinetic/Installation/Ubuntu). Note that the guidance and camera node of DJI for the M100 require to use the Indigo distribution.
|
||||
|
||||
* ROS additionnal dependencies:
|
||||
|
||||
You need the following package:
|
||||
|
||||
* mavros_msgs :
|
||||
|
||||
You can install using apt-get:
|
||||
|
||||
$ sudo apt-get install ros-<distro>-mavros ros-<distro>-mavros-extras
|
||||
```
|
||||
$ sudo apt-get install ros-<distro>-mavros ros-<distro>-mavros-extras
|
||||
```
|
||||
|
||||
Compilation
|
||||
===========
|
||||
|
||||
To compile the ros package, execute the following:
|
||||
|
||||
$ cd catkin_ws
|
||||
$ catkin_make
|
||||
$ source devel/setup.bash
|
||||
```
|
||||
mkdir -p ROS_WS/src
|
||||
cd ROS_WS/src
|
||||
git clone https://github.com/MISTLab/ROSBuzz rosbuzz
|
||||
cd ..
|
||||
catkin_make
|
||||
```
|
||||
|
||||
Run
|
||||
===
|
||||
|
@ -64,42 +45,50 @@ To run the ROSBuzz package using the launch file, execute the following:
|
|||
|
||||
$ roslaunch rosbuzz rosbuzz.launch
|
||||
|
||||
Note : Before launching the ROSBuzz node, verify all the parameters in the launch file. A launch file using gdb is available also (rosbuzzd.launch).
|
||||
Have a look at the launch file to understand what parameters are available to suit your usage. All topics and services names are listed in `launch_config/topics.yaml`. Note : Before launching the ROSBuzz node, verify all the parameters in the launch file. A launch file using gdb is available too (rosbuzzd.launch).
|
||||
|
||||
* Buzz scripts: Several behavioral scripts are included in the "buzz_Scripts" folder, such as "graphformGPS.bzz" uses in the ICRA publication below and the "testaloneWP.bzz" to control a single drone with a ".csv" list of waypoints. The script "empty.bzz" is a template script.
|
||||
* Buzz scripts: Several behavioral scripts are included in the "buzz_Scripts" folder, such as "graphformGPS.bzz" uses in [1] and the "testaloneWP.bzz" to control a single drone with a ".csv" list of waypoints. The script "empty.bzz" is a template script.
|
||||
|
||||
Publisher
|
||||
=========
|
||||
Publishers
|
||||
-----------
|
||||
|
||||
* Messages from Buzz (BVM):
|
||||
The package publishes mavros_msgs/Mavlink message "outMavlink".
|
||||
The node publishes `mavros_msgs/Mavlink` message "outMavlink".
|
||||
|
||||
* Command to the flight controller:
|
||||
The package publishes geometry_msgs/PoseStamped message "setpoint_position/local".
|
||||
The node publishes `geometry_msgs/PoseStamped message` "setpoint_position/local".
|
||||
|
||||
* Other information from the swarw:
|
||||
The node publishes:
|
||||
- "bvmstate" (`std_msgs/String`)
|
||||
- "neighbours_pos" (`rosbuzz_msgs/neigh_pos`)
|
||||
- "fleet_status" (`mavros_msgs/Mavlink`)
|
||||
|
||||
Subscribers
|
||||
-----------
|
||||
|
||||
* Current position of the Robot:
|
||||
The package subscribes to sensor_msgs/NavSatFix message "global_position/global", to a std_msgs/Float64 message "global_position/rel_alt" and to a geometry_msgs/PoseStamped message "local_position/pose".
|
||||
* Information from the Robot controller (mavros compliant):
|
||||
The node subscribes to:
|
||||
- "global_position/global" (`sensor_msgs/NavSatFix message`)
|
||||
- "global_position/rel_alt" (`std_msgs/Float64`)
|
||||
- "local_position/pose" (`geometry_msgs/PoseStamped`)
|
||||
- "battery" (`sensor_msgs/BatteryState`)
|
||||
- either "extended_state" (`mavros_msgs/ExtendedState`) or "state" (`mavros_msgs/State`)
|
||||
|
||||
* Messages to Buzz (BVM):
|
||||
The package subscribes to mavros_msgs/Mavlink message with a topic name of "inMavlink".
|
||||
The node subscribes to `mavros_msgs/Mavlink` incoming message with name "inMavlink".
|
||||
|
||||
* Status:
|
||||
The package subscribes to mavros_msgs/BatteryStatus message "battery" and to either a mavros_msgs/ExtendedState message "extended_state" or a mavros_msgs/State message "state".
|
||||
|
||||
Service
|
||||
Services
|
||||
-------
|
||||
|
||||
* Remote Controller:
|
||||
The package offers a mavros_msgs/CommandLong service "buzzcmd" to control its state. In the "misc" folder a bash script shows how to control the Buzz states from the command line.
|
||||
The package offers a service "buzzcmd" (`mavros_msgs/CommandLong`) to control it. In the "misc" folder, a bash script shows how to control the swarm state from the command line.
|
||||
|
||||
References
|
||||
------
|
||||
* ROS and Buzz : consensus-based behaviors for heterogeneous teams. St-Onge, D., Shankar Varadharajan, V., Li, G., Svogor, I. and Beltrame, G. arXiv : https://arxiv.org/abs/1710.08843
|
||||
* [1] ROS and Buzz : consensus-based behaviors for heterogeneous teams. St-Onge, D., Shankar Varadharajan, V., Li, G., Svogor, I. and Beltrame, G. arXiv : https://arxiv.org/abs/1710.08843
|
||||
|
||||
* Over-The-Air Updates for Robotic Swarms. Submitted to IEEE Software (August 2017). 8pgs. Shankar Varadharajan, V., St-Onge, D., Guß, C. and Beltrame, G.
|
||||
* [2] Over-The-Air Updates for Robotic Swarms. Submitted to IEEE Software (August 2017). 8pgs. Shankar Varadharajan, V., St-Onge, D., Guß, C. and Beltrame, G.
|
||||
|
||||
Visual Studio Code
|
||||
--------------------
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -8,43 +8,46 @@
|
|||
|
||||
#include "buzz_update.h"
|
||||
|
||||
namespace buzz_update{
|
||||
/*Temp for data collection*/
|
||||
// static int neigh=-1;
|
||||
static struct timeval t1, t2;
|
||||
static int timer_steps = 0;
|
||||
// static clock_t end;
|
||||
namespace buzz_update
|
||||
{
|
||||
/*Temp for data collection*/
|
||||
// static int neigh=-1;
|
||||
static struct timeval t1, t2;
|
||||
static int timer_steps = 0;
|
||||
// static clock_t end;
|
||||
|
||||
/*Temp end */
|
||||
static int fd, wd = 0;
|
||||
static int old_update = 0;
|
||||
static buzz_updater_elem_t updater;
|
||||
static int no_of_robot;
|
||||
static const char* dbgf_name;
|
||||
static const char* bcfname;
|
||||
static const char* old_bcfname = "old_bcode.bo";
|
||||
static const char* bzz_file;
|
||||
static int Robot_id = 0;
|
||||
static int neigh = -1;
|
||||
static int updater_msg_ready;
|
||||
static uint16_t update_try_counter = 0;
|
||||
static const uint16_t MAX_UPDATE_TRY = 5;
|
||||
static size_t old_byte_code_size = 0;
|
||||
static bool debug = false;
|
||||
/*Temp end */
|
||||
static int fd, wd = 0;
|
||||
static int old_update = 0;
|
||||
static buzz_updater_elem_t updater;
|
||||
static int no_of_robot;
|
||||
static const char* dbgf_name;
|
||||
static const char* bcfname;
|
||||
static const char* old_bcfname = "old_bcode.bo";
|
||||
static const char* bzz_file;
|
||||
static int Robot_id = 0;
|
||||
static int neigh = -1;
|
||||
static int updater_msg_ready;
|
||||
static uint16_t update_try_counter = 0;
|
||||
static const uint16_t MAX_UPDATE_TRY = 5;
|
||||
static size_t old_byte_code_size = 0;
|
||||
static bool debug = false;
|
||||
|
||||
/*Initialize updater*/
|
||||
int init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id)
|
||||
{
|
||||
/*Initialize updater*/
|
||||
int init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id)
|
||||
{
|
||||
buzzvm_t VM = buzz_utility::get_vm();
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "updates_active", 1));
|
||||
buzzvm_gload(VM);
|
||||
buzzobj_t obj = buzzvm_stack_at(VM, 1);
|
||||
if(obj->o.type == BUZZTYPE_INT && obj->i.value == 1){
|
||||
if (obj->o.type == BUZZTYPE_INT && obj->i.value == 1)
|
||||
{
|
||||
Robot_id = robot_id;
|
||||
dbgf_name = dbgfname;
|
||||
bcfname = bo_filename;
|
||||
ROS_WARN("UPDATES TURNED ON (modifying .bzz script file will update all robots)");
|
||||
if(debug) ROS_INFO("Initializing file monitor...");
|
||||
if (debug)
|
||||
ROS_INFO("Initializing file monitor...");
|
||||
fd = inotify_init1(IN_NONBLOCK);
|
||||
if (fd < 0)
|
||||
{
|
||||
|
@ -124,14 +127,15 @@ namespace buzz_update{
|
|||
fclose(fp);
|
||||
return 1;
|
||||
}
|
||||
else{
|
||||
else
|
||||
{
|
||||
ROS_WARN("UPDATES TURNED OFF... (Hint: Include update.bzz to turn on updates)");
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
/*Check for .bzz file chages*/
|
||||
int check_update()
|
||||
{
|
||||
}
|
||||
/*Check for .bzz file chages*/
|
||||
int check_update()
|
||||
{
|
||||
char buf[1024];
|
||||
int check = 0;
|
||||
int i = 0;
|
||||
|
@ -160,10 +164,10 @@ namespace buzz_update{
|
|||
if (!check)
|
||||
old_update = 0;
|
||||
return check;
|
||||
}
|
||||
}
|
||||
|
||||
int test_patch(std::string& path, std::string& name1, size_t update_patch_size, uint8_t* patch)
|
||||
{
|
||||
int test_patch(std::string& path, std::string& name1, size_t update_patch_size, uint8_t* patch)
|
||||
{
|
||||
if (SIMULATION == 1)
|
||||
{
|
||||
return 1;
|
||||
|
@ -180,22 +184,24 @@ namespace buzz_update{
|
|||
std::stringstream patch_exsisting;
|
||||
patch_exsisting << "bspatch " << path << name1 << ".bo " << path << name1 << "-patched.bo " << path << name1
|
||||
<< "tmp_patch.bo";
|
||||
if(debug) ROS_WARN("Launching bspatch command: %s", patch_exsisting.str().c_str());
|
||||
if (debug)
|
||||
ROS_WARN("Launching bspatch command: %s", patch_exsisting.str().c_str());
|
||||
if (system(patch_exsisting.str().c_str()))
|
||||
return 0;
|
||||
else
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
updater_code_t obtain_patched_bo(std::string& path, std::string& name1)
|
||||
{
|
||||
updater_code_t obtain_patched_bo(std::string& path, std::string& name1)
|
||||
{
|
||||
if (SIMULATION == 1)
|
||||
{
|
||||
/*Read the exsisting file to simulate the patching*/
|
||||
std::stringstream read_patched;
|
||||
read_patched << path << name1 << ".bo";
|
||||
if(debug){
|
||||
if (debug)
|
||||
{
|
||||
ROS_WARN("Simulation patching ...");
|
||||
ROS_WARN("Read file for patching %s", read_patched.str().c_str());
|
||||
}
|
||||
|
@ -228,7 +234,8 @@ namespace buzz_update{
|
|||
/*Read the new patched file*/
|
||||
std::stringstream read_patched;
|
||||
read_patched << path << name1 << "-patched.bo";
|
||||
if(debug) {
|
||||
if (debug)
|
||||
{
|
||||
ROS_WARN("Robot patching ...");
|
||||
ROS_WARN("Read file for patching %s", read_patched.str().c_str());
|
||||
}
|
||||
|
@ -260,10 +267,10 @@ namespace buzz_update{
|
|||
|
||||
return update_code;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void code_message_outqueue_append()
|
||||
{
|
||||
void code_message_outqueue_append()
|
||||
{
|
||||
updater->outmsg_queue = (updater_msgqueue_t)malloc(sizeof(struct updater_msgqueue_s));
|
||||
/* if size less than 250 Pad with zeors to assure transmission*/
|
||||
uint16_t size = UPDATE_CODE_HEADER_SIZE + *(size_t*)(updater->patch_size);
|
||||
|
@ -285,10 +292,10 @@ namespace buzz_update{
|
|||
memcpy(updater->outmsg_queue->queue + size, updater->patch, *(size_t*)(updater->patch_size));
|
||||
// size += (uint16_t) * (size_t*)(updater->patch_size);
|
||||
updater_msg_ready = 1;
|
||||
}
|
||||
}
|
||||
|
||||
void outqueue_append_code_request(uint16_t update_no)
|
||||
{
|
||||
void outqueue_append_code_request(uint16_t update_no)
|
||||
{
|
||||
updater->outmsg_queue = (updater_msgqueue_t)malloc(sizeof(struct updater_msgqueue_s));
|
||||
uint16_t size = 0;
|
||||
updater->outmsg_queue->queue = (uint8_t*)malloc(2 * sizeof(uint16_t) + sizeof(uint8_t) + CODE_REQUEST_PADDING);
|
||||
|
@ -304,28 +311,30 @@ namespace buzz_update{
|
|||
size += sizeof(uint16_t);
|
||||
*(uint16_t*)(updater->outmsg_queue->size) = size + CODE_REQUEST_PADDING;
|
||||
updater_msg_ready = 1;
|
||||
if(debug) ROS_WARN("[Debug] Requesting update no. %u for rebroadcast, try: %u", update_no, update_try_counter);
|
||||
}
|
||||
if (debug)
|
||||
ROS_WARN("[Debug] Requesting update no. %u for rebroadcast, try: %u", update_no, update_try_counter);
|
||||
}
|
||||
|
||||
void code_message_inqueue_append(uint8_t* msg, uint16_t size)
|
||||
{
|
||||
void code_message_inqueue_append(uint8_t* msg, uint16_t size)
|
||||
{
|
||||
updater->inmsg_queue = (updater_msgqueue_t)malloc(sizeof(struct updater_msgqueue_s));
|
||||
// ROS_INFO("[DEBUG] Updater append code of size %d", (int) size);
|
||||
updater->inmsg_queue->queue = (uint8_t*)malloc(size);
|
||||
updater->inmsg_queue->size = (uint8_t*)malloc(sizeof(uint16_t));
|
||||
memcpy(updater->inmsg_queue->queue, msg, size);
|
||||
*(uint16_t*)(updater->inmsg_queue->size) = size;
|
||||
}
|
||||
/*Used for data logging*/
|
||||
/*void set_packet_id(int packet_id)
|
||||
{
|
||||
}
|
||||
/*Used for data logging*/
|
||||
/*void set_packet_id(int packet_id)
|
||||
{
|
||||
packet_id_ = packet_id;
|
||||
}*/
|
||||
void code_message_inqueue_process()
|
||||
{
|
||||
}*/
|
||||
void code_message_inqueue_process()
|
||||
{
|
||||
int size = 0;
|
||||
updater_code_t out_code = NULL;
|
||||
if(debug) {
|
||||
if (debug)
|
||||
{
|
||||
ROS_WARN("[Debug] Updater processing in msg with mode %d", *(int*)(updater->mode));
|
||||
ROS_WARN("[Debug] Current update no: %u, Received update no: %u", (*(uint16_t*)(updater->update_no)),
|
||||
(*(uint16_t*)(updater->inmsg_queue->queue + sizeof(uint8_t))));
|
||||
|
@ -363,7 +372,8 @@ namespace buzz_update{
|
|||
|
||||
if (test_set_code((out_code->bcode), (char*)dbgf_name, (size_t)(*(uint16_t*)out_code->bcode_size)))
|
||||
{
|
||||
if(debug) ROS_WARN("Received patch PASSED tests!");
|
||||
if (debug)
|
||||
ROS_WARN("Received patch PASSED tests!");
|
||||
*(uint16_t*)updater->update_no = update_no;
|
||||
/*Clear exisiting patch if any*/
|
||||
delete_p(updater->patch);
|
||||
|
@ -391,7 +401,8 @@ namespace buzz_update{
|
|||
size = 0;
|
||||
if (*(uint8_t*)(updater->inmsg_queue->queue) == RESEND_CODE)
|
||||
{
|
||||
if(debug) ROS_WARN("Patch rebroadcast request received.");
|
||||
if (debug)
|
||||
ROS_WARN("Patch rebroadcast request received.");
|
||||
size += sizeof(uint8_t);
|
||||
if (*(uint16_t*)(updater->inmsg_queue->queue + size) == *(uint16_t*)(updater->update_no))
|
||||
{
|
||||
|
@ -399,7 +410,8 @@ namespace buzz_update{
|
|||
if (*(uint16_t*)(updater->inmsg_queue->queue + size) > update_try_counter)
|
||||
{
|
||||
update_try_counter = *(uint16_t*)(updater->inmsg_queue->queue + size);
|
||||
if(debug) ROS_WARN("Rebroadcasting patch, try : %u", update_try_counter);
|
||||
if (debug)
|
||||
ROS_WARN("Rebroadcasting patch, try : %u", update_try_counter);
|
||||
code_message_outqueue_append();
|
||||
}
|
||||
if (update_try_counter > MAX_UPDATE_TRY)
|
||||
|
@ -410,10 +422,10 @@ namespace buzz_update{
|
|||
delete_p(updater->inmsg_queue->queue);
|
||||
delete_p(updater->inmsg_queue->size);
|
||||
delete_p(updater->inmsg_queue);
|
||||
}
|
||||
}
|
||||
|
||||
void create_update_patch()
|
||||
{
|
||||
void create_update_patch()
|
||||
{
|
||||
std::stringstream genpatch;
|
||||
|
||||
std::string bzzfile_name(bzz_file);
|
||||
|
@ -427,7 +439,8 @@ namespace buzz_update{
|
|||
|
||||
/*Launch bsdiff and create a patch*/
|
||||
genpatch << "bsdiff " << path << name1 << ".bo " << path << name2 << ".bo " << path << "diff.bo";
|
||||
if(debug) ROS_WARN("Launching bsdiff: %s", genpatch.str().c_str());
|
||||
if (debug)
|
||||
ROS_WARN("Launching bsdiff: %s", genpatch.str().c_str());
|
||||
system(genpatch.str().c_str());
|
||||
|
||||
/*Delete old files & rename new files*/
|
||||
|
@ -463,10 +476,10 @@ namespace buzz_update{
|
|||
|
||||
/* Delete the diff file */
|
||||
remove(patchfileName.str().c_str());
|
||||
}
|
||||
}
|
||||
|
||||
void update_routine()
|
||||
{
|
||||
void update_routine()
|
||||
{
|
||||
buzzvm_t VM = buzz_utility::get_vm();
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
|
||||
buzzvm_pushi(VM, *(uint16_t*)(updater->update_no));
|
||||
|
@ -514,12 +527,14 @@ namespace buzz_update{
|
|||
|
||||
create_update_patch();
|
||||
VM = buzz_utility::get_vm();
|
||||
if(debug) ROS_INFO("Current Update no %d", *(uint16_t*)(updater->update_no));
|
||||
if (debug)
|
||||
ROS_INFO("Current Update no %d", *(uint16_t*)(updater->update_no));
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
|
||||
buzzvm_pushi(VM, *(uint16_t*)(updater->update_no));
|
||||
buzzvm_gstore(VM);
|
||||
neigh = -1;
|
||||
if(debug) ROS_INFO("Broadcasting patch ...");
|
||||
if (debug)
|
||||
ROS_INFO("Broadcasting patch ...");
|
||||
code_message_outqueue_append();
|
||||
}
|
||||
delete_p(BO_BUF);
|
||||
|
@ -556,30 +571,32 @@ namespace buzz_update{
|
|||
timer_steps = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t* getupdater_out_msg()
|
||||
{
|
||||
uint8_t* getupdater_out_msg()
|
||||
{
|
||||
return (uint8_t*)updater->outmsg_queue->queue;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t* getupdate_out_msg_size()
|
||||
{
|
||||
uint8_t* getupdate_out_msg_size()
|
||||
{
|
||||
// fprintf(stdout,"[Debug from get out size in util: ]size = %i \n",*(uint16_t*)updater->outmsg_queue->size);
|
||||
return (uint8_t*)updater->outmsg_queue->size;
|
||||
}
|
||||
}
|
||||
|
||||
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size)
|
||||
{
|
||||
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size)
|
||||
{
|
||||
if (buzz_utility::buzz_update_init_test(BO_BUF, dbgfname, bcode_size))
|
||||
{
|
||||
if(debug) ROS_WARN("Initializtion test passed");
|
||||
if (debug)
|
||||
ROS_WARN("Initializtion test passed");
|
||||
if (buzz_utility::update_step_test())
|
||||
{
|
||||
/*data logging*/
|
||||
old_byte_code_size = *(size_t*)updater->bcode_size;
|
||||
/*data logging*/
|
||||
if(debug) ROS_WARN("Step test passed");
|
||||
if (debug)
|
||||
ROS_WARN("Step test passed");
|
||||
*(int*)(updater->mode) = CODE_STANDBY;
|
||||
// fprintf(stdout,"updater value = %i\n",updater->mode);
|
||||
delete_p(updater->bcode);
|
||||
|
@ -637,27 +654,27 @@ namespace buzz_update{
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void destroy_out_msg_queue()
|
||||
{
|
||||
void destroy_out_msg_queue()
|
||||
{
|
||||
// fprintf(stdout,"out queue freed\n");
|
||||
delete_p(updater->outmsg_queue->queue);
|
||||
delete_p(updater->outmsg_queue->size);
|
||||
delete_p(updater->outmsg_queue);
|
||||
updater_msg_ready = 0;
|
||||
}
|
||||
}
|
||||
|
||||
int is_msg_present()
|
||||
{
|
||||
int is_msg_present()
|
||||
{
|
||||
return updater_msg_ready;
|
||||
}
|
||||
/*buzz_updater_elem_t get_updater()
|
||||
{
|
||||
}
|
||||
/*buzz_updater_elem_t get_updater()
|
||||
{
|
||||
return updater;
|
||||
}*/
|
||||
void destroy_updater()
|
||||
{
|
||||
}*/
|
||||
void destroy_updater()
|
||||
{
|
||||
delete_p(updater->bcode);
|
||||
delete_p(updater->bcode_size);
|
||||
delete_p(updater->standby_bcode);
|
||||
|
@ -678,24 +695,24 @@ namespace buzz_update{
|
|||
}
|
||||
inotify_rm_watch(fd, wd);
|
||||
close(fd);
|
||||
}
|
||||
}
|
||||
|
||||
void set_bzz_file(const char* in_bzz_file, bool dbg)
|
||||
{
|
||||
debug=dbg;
|
||||
void set_bzz_file(const char* in_bzz_file, bool dbg)
|
||||
{
|
||||
debug = dbg;
|
||||
bzz_file = in_bzz_file;
|
||||
}
|
||||
}
|
||||
|
||||
void updates_set_robots(int robots)
|
||||
{
|
||||
void updates_set_robots(int robots)
|
||||
{
|
||||
no_of_robot = robots;
|
||||
}
|
||||
}
|
||||
|
||||
/*--------------------------------------------------------
|
||||
/ Create Buzz bytecode from the bzz script input
|
||||
/-------------------------------------------------------*/
|
||||
int compile_bzz(std::string bzz_file)
|
||||
{
|
||||
/*--------------------------------------------------------
|
||||
/ Create Buzz bytecode from the bzz script input
|
||||
/-------------------------------------------------------*/
|
||||
int compile_bzz(std::string bzz_file)
|
||||
{
|
||||
/*Compile the buzz code .bzz to .bo*/
|
||||
std::string bzzfile_name(bzz_file);
|
||||
stringstream bzzfile_in_compile;
|
||||
|
@ -708,17 +725,17 @@ namespace buzz_update{
|
|||
bzzfile_in_compile << bzzfile_name;
|
||||
ROS_WARN("Launching buzz compilation for update: %s", bzzfile_in_compile.str().c_str());
|
||||
return system(bzzfile_in_compile.str().c_str());
|
||||
}
|
||||
}
|
||||
|
||||
/*void collect_data(std::ofstream& logger)
|
||||
{
|
||||
/*void collect_data(std::ofstream& logger)
|
||||
{
|
||||
double time_spent = (t2.tv_sec - t1.tv_sec) * 1000.0; //(double)(end - begin) / CLOCKS_PER_SEC;
|
||||
time_spent += (t2.tv_usec - t1.tv_usec) / 1000.0;
|
||||
// RID,update trigger,time steps taken,old byte code size, new bytecode size, patch size,update number,
|
||||
//
|
||||
Patch_packets_received_counter,Patch_request_packets_received,Patch_packets_sent_counter,Patch_request_packets_sent_counter
|
||||
Patch_packets_received_counter,Patch_request_packets_received,Patch_packets_sent_counter,Patch_request_packets_sent_counter
|
||||
logger << (int)no_of_robot << "," << neigh << "," << (double)time_spent << "," << (int)timer_steps << ","
|
||||
<< old_byte_code_size << "," << *(size_t*)updater->bcode_size << "," << *(size_t*)updater->patch_size << ","
|
||||
<< (int)*(uint8_t*)updater->update_no << "," << (int)packet_id_;
|
||||
}*/
|
||||
}*/
|
||||
}
|
|
@ -17,7 +17,7 @@ static buzzvm_t VM = 0;
|
|||
static char* BO_FNAME = 0;
|
||||
static uint8_t* BO_BUF = 0;
|
||||
static buzzdebug_t DBG_INFO = 0;
|
||||
static uint32_t MAX_MSG_SIZE = 190;//250; // Maximum Msg size for sending update packets
|
||||
static uint32_t MAX_MSG_SIZE = 190; // 250; // Maximum Msg size for sending update packets
|
||||
static uint8_t Robot_id = 0;
|
||||
static std::vector<uint8_t*> IN_MSG;
|
||||
std::map<int, Pos_struct> users_map;
|
||||
|
@ -572,7 +572,8 @@ int get_inmsg_size()
|
|||
return IN_MSG.size();
|
||||
}
|
||||
|
||||
std::vector<uint8_t*> get_inmsg_vector(){
|
||||
std::vector<uint8_t*> get_inmsg_vector()
|
||||
{
|
||||
return IN_MSG;
|
||||
}
|
||||
|
||||
|
@ -590,11 +591,12 @@ string get_bvmstate()
|
|||
---------------------------------------*/
|
||||
{
|
||||
std::string uav_state = "Unknown";
|
||||
if(VM && VM->strings){
|
||||
if (VM && VM->strings)
|
||||
{
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "BVMSTATE", 1));
|
||||
buzzvm_gload(VM);
|
||||
buzzobj_t obj = buzzvm_stack_at(VM, 1);
|
||||
if(obj->o.type == BUZZTYPE_STRING)
|
||||
if (obj->o.type == BUZZTYPE_STRING)
|
||||
uav_state = string(obj->s.value.str);
|
||||
else
|
||||
uav_state = "Not Available";
|
||||
|
@ -603,8 +605,8 @@ string get_bvmstate()
|
|||
return uav_state;
|
||||
}
|
||||
|
||||
int get_swarmsize() {
|
||||
int get_swarmsize()
|
||||
{
|
||||
return (int)buzzdict_size(VM->swarmmembers) + 1;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -45,8 +45,12 @@ struct Point
|
|||
{
|
||||
float x;
|
||||
float y;
|
||||
Point(): x( 0.0 ), y( 0.0 ) { }
|
||||
Point( float x, float y ): x( x ), y( y ) { }
|
||||
Point() : x(0.0), y(0.0)
|
||||
{
|
||||
}
|
||||
Point(float x, float y) : x(x), y(y)
|
||||
{
|
||||
}
|
||||
};
|
||||
string WPlistname = "";
|
||||
|
||||
|
@ -54,7 +58,7 @@ std::map<int, buzz_utility::RB_struct> targets_map;
|
|||
std::map<int, buzz_utility::RB_struct> wplist_map;
|
||||
std::map<int, buzz_utility::Pos_struct> neighbors_map;
|
||||
std::map<int, buzz_utility::neighbors_status> neighbors_status_map;
|
||||
std::map<int, std::map<int,int>> grid;
|
||||
std::map<int, std::map<int, int>> grid;
|
||||
|
||||
/****************************************/
|
||||
/****************************************/
|
||||
|
@ -123,7 +127,8 @@ void setVorlog(string path)
|
|||
/ set the absolute path for a csv list of waypoints
|
||||
----------------------------------------------------------- */
|
||||
{
|
||||
voronoicsv.open(path + "/log/voronoi_"+std::to_string(buzz_utility::get_robotid())+".csv", std::ios_base::trunc | std::ios_base::out);
|
||||
voronoicsv.open(path + "/log/voronoi_" + std::to_string(buzz_utility::get_robotid()) + ".csv",
|
||||
std::ios_base::trunc | std::ios_base::out);
|
||||
logVoronoi = true;
|
||||
}
|
||||
|
||||
|
@ -152,15 +157,18 @@ void rb_from_gps(double nei[], double out[], double cur[])
|
|||
out[2] = 0.0;
|
||||
}
|
||||
|
||||
void gps_from_vec(double vec[], double gps[]) {
|
||||
void gps_from_vec(double vec[], double gps[])
|
||||
{
|
||||
double Vrange = sqrt(vec[0] * vec[0] + vec[1] * vec[1]);
|
||||
double Vbearing = constrainAngle(atan2(vec[1], vec[0]));
|
||||
double latR = cur_pos[0]*M_PI/180.0;
|
||||
double lonR = cur_pos[1]*M_PI/180.0;
|
||||
double target_lat = asin(sin(latR) * cos(Vrange/EARTH_RADIUS) + cos(latR) * sin(Vrange/EARTH_RADIUS) * cos(Vbearing));
|
||||
double target_lon = lonR + atan2(sin(Vbearing) * sin(Vrange/EARTH_RADIUS) * cos(latR), cos(Vrange/EARTH_RADIUS) - sin(latR) * sin(target_lat));
|
||||
gps[0] = target_lat*180.0/M_PI;
|
||||
gps[1] = target_lon*180.0/M_PI;
|
||||
double latR = cur_pos[0] * M_PI / 180.0;
|
||||
double lonR = cur_pos[1] * M_PI / 180.0;
|
||||
double target_lat =
|
||||
asin(sin(latR) * cos(Vrange / EARTH_RADIUS) + cos(latR) * sin(Vrange / EARTH_RADIUS) * cos(Vbearing));
|
||||
double target_lon = lonR + atan2(sin(Vbearing) * sin(Vrange / EARTH_RADIUS) * cos(latR),
|
||||
cos(Vrange / EARTH_RADIUS) - sin(latR) * sin(target_lat));
|
||||
gps[0] = target_lat * 180.0 / M_PI;
|
||||
gps[1] = target_lon * 180.0 / M_PI;
|
||||
gps[2] = cur_pos[2];
|
||||
}
|
||||
|
||||
|
@ -215,7 +223,7 @@ void parse_gpslist()
|
|||
fin.close();
|
||||
}
|
||||
|
||||
void check_targets_sim(double lat, double lon, double *res)
|
||||
void check_targets_sim(double lat, double lon, double* res)
|
||||
/*
|
||||
/ check if a listed target is close
|
||||
----------------------------------------------------------- */
|
||||
|
@ -225,16 +233,19 @@ void check_targets_sim(double lat, double lon, double *res)
|
|||
for (it = wplist_map.begin(); it != wplist_map.end(); ++it)
|
||||
{
|
||||
double rb[3];
|
||||
double ref[2]={lat, lon};
|
||||
double tar[2]={it->second.latitude, it->second.longitude};
|
||||
double ref[2] = { lat, lon };
|
||||
double tar[2] = { it->second.latitude, it->second.longitude };
|
||||
rb_from_gps(tar, rb, ref);
|
||||
if(rb[0] < visibility_radius && (buzz_utility::get_bvmstate()=="WAYPOINT" && it->second.r==0)){
|
||||
if (rb[0] < visibility_radius && (buzz_utility::get_bvmstate() == "WAYPOINT" && it->second.r == 0))
|
||||
{
|
||||
ROS_WARN("FOUND A TARGET IN WAYPOINT!!! [%i]", it->first);
|
||||
res[0] = it->first;
|
||||
res[1] = it->second.latitude;
|
||||
res[2] = it->second.longitude;
|
||||
res[3] = it->second.altitude;
|
||||
} else if(rb[0] < visibility_radius && (buzz_utility::get_bvmstate()=="DEPLOY" && it->second.r==1)){
|
||||
}
|
||||
else if (rb[0] < visibility_radius && (buzz_utility::get_bvmstate() == "DEPLOY" && it->second.r == 1))
|
||||
{
|
||||
ROS_WARN("FOUND A TARGET IN WAYPOINT!!! [%i]", it->first);
|
||||
res[0] = it->first;
|
||||
res[1] = it->second.latitude;
|
||||
|
@ -255,19 +266,21 @@ int buzz_exportmap(buzzvm_t vm)
|
|||
buzzvm_lload(vm, 1);
|
||||
buzzvm_type_assert(vm, 1, BUZZTYPE_TABLE); // dictionary
|
||||
buzzobj_t t = buzzvm_stack_at(vm, 1);
|
||||
for(int32_t i = 1; i <= buzzdict_size(t->t.value); ++i) {
|
||||
for (int32_t i = 1; i <= buzzdict_size(t->t.value); ++i)
|
||||
{
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushi(vm, i);
|
||||
buzzvm_tget(vm);
|
||||
std::map<int, int> row;
|
||||
for(int32_t j = 1; j <= buzzdict_size(buzzvm_stack_at(vm, 1)->t.value); ++j) {
|
||||
for (int32_t j = 1; j <= buzzdict_size(buzzvm_stack_at(vm, 1)->t.value); ++j)
|
||||
{
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushi(vm, j);
|
||||
buzzvm_tget(vm);
|
||||
row.insert(std::pair<int,int>(j, 100.0 - round(buzzvm_stack_at(vm, 1)->f.value*100.0)));
|
||||
row.insert(std::pair<int, int>(j, 100.0 - round(buzzvm_stack_at(vm, 1)->f.value * 100.0)));
|
||||
buzzvm_pop(vm);
|
||||
}
|
||||
grid.insert(std::pair<int,std::map<int, int>>(i,row));
|
||||
grid.insert(std::pair<int, std::map<int, int>>(i, row));
|
||||
buzzvm_pop(vm);
|
||||
}
|
||||
// DEBUG
|
||||
|
@ -284,8 +297,7 @@ int buzz_exportmap(buzzvm_t vm)
|
|||
// point q lies on line segment 'pr'
|
||||
bool onSegment(Point p, Point q, Point r)
|
||||
{
|
||||
if (q.x <= max(p.x, r.x) && q.x >= min(p.x, r.x) &&
|
||||
q.y <= max(p.y, r.y) && q.y >= min(p.y, r.y))
|
||||
if (q.x <= max(p.x, r.x) && q.x >= min(p.x, r.x) && q.y <= max(p.y, r.y) && q.y >= min(p.y, r.y))
|
||||
return true;
|
||||
return false;
|
||||
}
|
||||
|
@ -296,11 +308,11 @@ bool onSegment(Point p, Point q, Point r)
|
|||
// 2 --> Counterclockwise
|
||||
int orientation(Point p, Point q, Point r)
|
||||
{
|
||||
int val =round((q.y - p.y) * (r.x - q.x)*100 -
|
||||
(q.x - p.x) * (r.y - q.y)*100);
|
||||
int val = round((q.y - p.y) * (r.x - q.x) * 100 - (q.x - p.x) * (r.y - q.y) * 100);
|
||||
|
||||
if (val == 0) return 0; // colinear
|
||||
return (val > 0)? 1: 2; // clock or counterclock wise
|
||||
if (val == 0)
|
||||
return 0; // colinear
|
||||
return (val > 0) ? 1 : 2; // clock or counterclock wise
|
||||
}
|
||||
// The function that returns true if line segment 'p1q1'
|
||||
// and 'p2q2' intersect.
|
||||
|
@ -313,7 +325,7 @@ bool doIntersect(Point p1, Point q1, Point p2, Point q2)
|
|||
int o3 = orientation(p2, q2, p1);
|
||||
int o4 = orientation(p2, q2, q1);
|
||||
|
||||
//ROS_WARN("(%f,%f)->(%f,%f), 1:%d,2:%d,3:%d,4:%d",p1.x,p1.y,q1.x,q1.y,o1,o2,o3,o4);
|
||||
// ROS_WARN("(%f,%f)->(%f,%f), 1:%d,2:%d,3:%d,4:%d",p1.x,p1.y,q1.x,q1.y,o1,o2,o3,o4);
|
||||
|
||||
// General case
|
||||
if (o1 != o2 && o3 != o4)
|
||||
|
@ -321,115 +333,133 @@ bool doIntersect(Point p1, Point q1, Point p2, Point q2)
|
|||
|
||||
// Special Cases
|
||||
// p1, q1 and p2 are colinear and p2 lies on segment p1q1
|
||||
if (o1 == 0 && onSegment(p1, p2, q1)) return true;
|
||||
if (o1 == 0 && onSegment(p1, p2, q1))
|
||||
return true;
|
||||
|
||||
// p1, q1 and p2 are colinear and q2 lies on segment p1q1
|
||||
if (o2 == 0 && onSegment(p1, q2, q1)) return true;
|
||||
if (o2 == 0 && onSegment(p1, q2, q1))
|
||||
return true;
|
||||
|
||||
// p2, q2 and p1 are colinear and p1 lies on segment p2q2
|
||||
if (o3 == 0 && onSegment(p2, p1, q2)) return true;
|
||||
if (o3 == 0 && onSegment(p2, p1, q2))
|
||||
return true;
|
||||
|
||||
// p2, q2 and q1 are colinear and q1 lies on segment p2q2
|
||||
if (o4 == 0 && onSegment(p2, q1, q2)) return true;
|
||||
if (o4 == 0 && onSegment(p2, q1, q2))
|
||||
return true;
|
||||
|
||||
return false; // Doesn't fall in any of the above cases
|
||||
}
|
||||
|
||||
float clockwise_angle_of( const Point& p )
|
||||
float clockwise_angle_of(const Point& p)
|
||||
{
|
||||
return atan2(p.y,p.x);
|
||||
return atan2(p.y, p.x);
|
||||
}
|
||||
|
||||
bool clockwise_compare_points( const Point& a, const Point& b )
|
||||
bool clockwise_compare_points(const Point& a, const Point& b)
|
||||
{
|
||||
return clockwise_angle_of( a ) < clockwise_angle_of( b );
|
||||
return clockwise_angle_of(a) < clockwise_angle_of(b);
|
||||
}
|
||||
|
||||
void sortclose_polygon(vector <Point> *P){
|
||||
std::sort( P->begin(), P->end(), clockwise_compare_points );
|
||||
void sortclose_polygon(vector<Point>* P)
|
||||
{
|
||||
std::sort(P->begin(), P->end(), clockwise_compare_points);
|
||||
P->push_back((*P)[0]);
|
||||
}
|
||||
|
||||
|
||||
float pol_area(vector <Point> vert) {
|
||||
float pol_area(vector<Point> vert)
|
||||
{
|
||||
float a = 0.0;
|
||||
//ROS_INFO("Polygone %d edges area.",vert.size());
|
||||
vector <Point>::iterator it;
|
||||
vector <Point>::iterator next;
|
||||
for (it = vert.begin(); it != vert.end()-1; ++it){
|
||||
next = it+1;
|
||||
// ROS_INFO("Polygone %d edges area.",vert.size());
|
||||
vector<Point>::iterator it;
|
||||
vector<Point>::iterator next;
|
||||
for (it = vert.begin(); it != vert.end() - 1; ++it)
|
||||
{
|
||||
next = it + 1;
|
||||
a += it->x * next->y - next->x * it->y;
|
||||
}
|
||||
a *= 0.5;
|
||||
//ROS_INFO("Polygon area: %f",a);
|
||||
// ROS_INFO("Polygon area: %f",a);
|
||||
return a;
|
||||
}
|
||||
|
||||
double* polygone_center(vector <Point> vert, double *c) {
|
||||
double* polygone_center(vector<Point> vert, double* c)
|
||||
{
|
||||
float A = pol_area(vert);
|
||||
int i1 = 1;
|
||||
vector <Point>::iterator it;
|
||||
vector <Point>::iterator next;
|
||||
for (it = vert.begin(); it != vert.end()-1; ++it){
|
||||
next = it+1;
|
||||
float t = it->x*next->y - next->x*it->y;
|
||||
c[0] += (it->x+next->x) * t;
|
||||
c[1] += (it->y+next->y) * t;
|
||||
vector<Point>::iterator it;
|
||||
vector<Point>::iterator next;
|
||||
for (it = vert.begin(); it != vert.end() - 1; ++it)
|
||||
{
|
||||
next = it + 1;
|
||||
float t = it->x * next->y - next->x * it->y;
|
||||
c[0] += (it->x + next->x) * t;
|
||||
c[1] += (it->y + next->y) * t;
|
||||
}
|
||||
c[0] = c[0] / (6.0 * A);
|
||||
c[1] = c[1] / (6.0 * A);
|
||||
return c;
|
||||
}
|
||||
|
||||
double numerator ( Point A, Point C, Point E, Point F ) { return (A.y - C.y) * (F.x - E.x) - (A.x - C.x) * (F.y - E.y); }
|
||||
double denominator( Point A, Point B, Point C, Point D ) { return (B.x - A.x) * (D.y - C.y) - (B.y - A.y) * (D.x - C.x); }
|
||||
double numerator(Point A, Point C, Point E, Point F)
|
||||
{
|
||||
return (A.y - C.y) * (F.x - E.x) - (A.x - C.x) * (F.y - E.y);
|
||||
}
|
||||
double denominator(Point A, Point B, Point C, Point D)
|
||||
{
|
||||
return (B.x - A.x) * (D.y - C.y) - (B.y - A.y) * (D.x - C.x);
|
||||
}
|
||||
|
||||
void getintersection(Point S, Point D, std::vector <Point> Poly, Point *I) {
|
||||
//printf("Points for intersection 1(%f,%f->%f,%f) and 2(%f,%f->%f,%f)\n",q1.x,q1.y,p1.x,p1.y,q2.x,q2.y,p2.x,p2.y);
|
||||
void getintersection(Point S, Point D, std::vector<Point> Poly, Point* I)
|
||||
{
|
||||
// printf("Points for intersection 1(%f,%f->%f,%f) and 2(%f,%f->%f,%f)\n",q1.x,q1.y,p1.x,p1.y,q2.x,q2.y,p2.x,p2.y);
|
||||
bool parallel = false;
|
||||
bool collinear = false;
|
||||
std::vector <Point>::iterator itc;
|
||||
std::vector <Point>::iterator next;
|
||||
for (itc = Poly.begin(); itc != Poly.end()-1; ++itc) {
|
||||
next = itc+1;
|
||||
std::vector<Point>::iterator itc;
|
||||
std::vector<Point>::iterator next;
|
||||
for (itc = Poly.begin(); itc != Poly.end() - 1; ++itc)
|
||||
{
|
||||
next = itc + 1;
|
||||
if (doIntersect((*itc), (*next), S, D))
|
||||
{
|
||||
// Uses the determinant of the two lines. For more information, refer to one of the following:
|
||||
// https://en.wikipedia.org/wiki/Line%E2%80%93line_intersection#Given_two_points_on_each_line
|
||||
// http://www.faqs.org/faqs/graphics/algorithms-faq/ (Subject 1.03)
|
||||
|
||||
double d = denominator( S, D, (*itc), (*next) );
|
||||
double d = denominator(S, D, (*itc), (*next));
|
||||
|
||||
if (std::abs( d ) < 0.000000001)
|
||||
if (std::abs(d) < 0.000000001)
|
||||
{
|
||||
parallel = true;
|
||||
collinear = abs(numerator( S, D, (*itc), (*next) )) < 0.000000001;
|
||||
collinear = abs(numerator(S, D, (*itc), (*next))) < 0.000000001;
|
||||
return;
|
||||
}
|
||||
|
||||
double r = numerator( S, (*itc), (*itc), (*next) ) / d;
|
||||
double s = numerator( S, (*itc), S, D ) / d;
|
||||
double r = numerator(S, (*itc), (*itc), (*next)) / d;
|
||||
double s = numerator(S, (*itc), S, D) / d;
|
||||
|
||||
//ROS_INFO("-- (%f,%f)",S.x + r * (D.x - S.x), S.y + r * (D.y - S.y));
|
||||
(*I)=Point(S.x + r * (D.x - S.x), S.y + r * (D.y - S.y));
|
||||
// ROS_INFO("-- (%f,%f)",S.x + r * (D.x - S.x), S.y + r * (D.y - S.y));
|
||||
(*I) = Point(S.x + r * (D.x - S.x), S.y + r * (D.y - S.y));
|
||||
}
|
||||
}
|
||||
if(parallel || collinear)
|
||||
ROS_WARN("Lines are Collinear (%d) or Parallels (%d)",collinear,parallel);
|
||||
if (parallel || collinear)
|
||||
ROS_WARN("Lines are Collinear (%d) or Parallels (%d)", collinear, parallel);
|
||||
}
|
||||
|
||||
bool isSiteout(Point S, std::vector <Point> Poly) {
|
||||
bool isSiteout(Point S, std::vector<Point> Poly)
|
||||
{
|
||||
bool onedge = false;
|
||||
|
||||
// Create a point for line segment from p to infinite
|
||||
Point extreme = {10000, S.y};
|
||||
Point extreme = { 10000, S.y };
|
||||
|
||||
// Count intersections of the above line with sides of polygon
|
||||
int count = 0;
|
||||
std::vector <Point>::iterator itc;
|
||||
std::vector <Point>::iterator next;
|
||||
for (itc = Poly.begin(); itc != Poly.end()-1; ++itc) {
|
||||
next = itc+1;
|
||||
std::vector<Point>::iterator itc;
|
||||
std::vector<Point>::iterator next;
|
||||
for (itc = Poly.begin(); itc != Poly.end() - 1; ++itc)
|
||||
{
|
||||
next = itc + 1;
|
||||
|
||||
// Check if the line segment from 'p' to 'extreme' intersects
|
||||
// with the line segment from 'polygon[i]' to 'polygon[next]'
|
||||
|
@ -438,16 +468,17 @@ bool isSiteout(Point S, std::vector <Point> Poly) {
|
|||
// If the point 'p' is colinear with line segment 'i-next',
|
||||
// then check if it lies on segment. If it lies, return true,
|
||||
// otherwise false
|
||||
if (orientation((*itc), S, (*next)) == 0) {
|
||||
if (orientation((*itc), S, (*next)) == 0)
|
||||
{
|
||||
onedge = onSegment((*itc), S, (*next));
|
||||
if(onedge)
|
||||
if (onedge)
|
||||
break;
|
||||
}
|
||||
count++;
|
||||
}
|
||||
}
|
||||
|
||||
return ((count%2 == 0) && !onedge);
|
||||
return ((count % 2 == 0) && !onedge);
|
||||
}
|
||||
|
||||
int buzzuav_geofence(buzzvm_t vm)
|
||||
|
@ -459,12 +490,14 @@ int buzzuav_geofence(buzzvm_t vm)
|
|||
buzzvm_type_assert(vm, 1, BUZZTYPE_TABLE); // dictionary
|
||||
buzzobj_t t = buzzvm_stack_at(vm, 1);
|
||||
|
||||
if(buzzdict_size(t->t.value) < 5) {
|
||||
if (buzzdict_size(t->t.value) < 5)
|
||||
{
|
||||
ROS_ERROR("Wrong Geofence input size (%i).", buzzdict_size(t->t.value));
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
std::vector <Point> polygon_bound;
|
||||
for(int32_t i = 0; i < buzzdict_size(t->t.value); ++i) {
|
||||
std::vector<Point> polygon_bound;
|
||||
for (int32_t i = 0; i < buzzdict_size(t->t.value); ++i)
|
||||
{
|
||||
Point tmp;
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushi(vm, i);
|
||||
|
@ -473,28 +506,34 @@ int buzzuav_geofence(buzzvm_t vm)
|
|||
buzzvm_dup(vm);
|
||||
buzzvm_pushs(vm, buzzvm_string_register(vm, "x", 1));
|
||||
buzzvm_tget(vm);
|
||||
if(i==0){
|
||||
if (i == 0)
|
||||
{
|
||||
P.x = buzzvm_stack_at(vm, 1)->f.value;
|
||||
//printf("px=%f\n",P.x);
|
||||
}else{
|
||||
// printf("px=%f\n",P.x);
|
||||
}
|
||||
else
|
||||
{
|
||||
tmp.x = buzzvm_stack_at(vm, 1)->f.value;
|
||||
//printf("c%dx=%f\n",i,tmp.x);
|
||||
// printf("c%dx=%f\n",i,tmp.x);
|
||||
}
|
||||
buzzvm_pop(vm);
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushs(vm, buzzvm_string_register(vm, "y", 1));
|
||||
buzzvm_tget(vm);
|
||||
//ROS_INFO("[%i]---y-->%i",buzz_utility::get_robotid(), tmp);
|
||||
if(i==0){
|
||||
// ROS_INFO("[%i]---y-->%i",buzz_utility::get_robotid(), tmp);
|
||||
if (i == 0)
|
||||
{
|
||||
P.y = buzzvm_stack_at(vm, 1)->f.value;
|
||||
//printf("py=%f\n",P.y);
|
||||
}else{
|
||||
// printf("py=%f\n",P.y);
|
||||
}
|
||||
else
|
||||
{
|
||||
tmp.y = buzzvm_stack_at(vm, 1)->f.value;
|
||||
//printf("c%dy=%f\n",i,tmp.y);
|
||||
// printf("c%dy=%f\n",i,tmp.y);
|
||||
}
|
||||
buzzvm_pop(vm);
|
||||
|
||||
if(i!=0)
|
||||
if (i != 0)
|
||||
polygon_bound.push_back(tmp);
|
||||
|
||||
buzzvm_pop(vm);
|
||||
|
@ -502,21 +541,22 @@ int buzzuav_geofence(buzzvm_t vm)
|
|||
sortclose_polygon(&polygon_bound);
|
||||
|
||||
// Check if we are in the zone
|
||||
if(isSiteout(P, polygon_bound)){
|
||||
if (isSiteout(P, polygon_bound))
|
||||
{
|
||||
Point Intersection;
|
||||
getintersection(Point(0.0, 0.0) , P, polygon_bound, &Intersection);
|
||||
getintersection(Point(0.0, 0.0), P, polygon_bound, &Intersection);
|
||||
double gps[3];
|
||||
double d[2]={Intersection.x,Intersection.y};
|
||||
double d[2] = { Intersection.x, Intersection.y };
|
||||
gps_from_vec(d, gps);
|
||||
set_gpsgoal(gps);
|
||||
ROS_WARN("Geofencing trigered, not going any further (%f,%f)!",d[0],d[1]);
|
||||
ROS_WARN("Geofencing trigered, not going any further (%f,%f)!", d[0], d[1]);
|
||||
}
|
||||
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
|
||||
int voronoi_center(buzzvm_t vm) {
|
||||
|
||||
int voronoi_center(buzzvm_t vm)
|
||||
{
|
||||
float dist_max = 300;
|
||||
|
||||
buzzvm_lnum_assert(vm, 1);
|
||||
|
@ -531,8 +571,9 @@ int voronoi_center(buzzvm_t vm) {
|
|||
int Poly_vert = buzzvm_stack_at(vm, 1)->i.value;
|
||||
buzzvm_pop(vm);
|
||||
|
||||
std::vector <Point> polygon_bound;
|
||||
for(int32_t i = 0; i < Poly_vert; ++i) {
|
||||
std::vector<Point> polygon_bound;
|
||||
for (int32_t i = 0; i < Poly_vert; ++i)
|
||||
{
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushi(vm, i);
|
||||
buzzvm_tget(vm);
|
||||
|
@ -540,28 +581,49 @@ int voronoi_center(buzzvm_t vm) {
|
|||
buzzvm_dup(vm);
|
||||
buzzvm_pushs(vm, buzzvm_string_register(vm, "x", 1));
|
||||
buzzvm_tget(vm);
|
||||
//ROS_INFO("---x-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
// ROS_INFO("---x-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
float tmpx = buzzvm_stack_at(vm, 1)->f.value;
|
||||
buzzvm_pop(vm);
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushs(vm, buzzvm_string_register(vm, "y", 1));
|
||||
buzzvm_tget(vm);
|
||||
//ROS_INFO("---y-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
// ROS_INFO("---y-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
float tmpy = buzzvm_stack_at(vm, 1)->f.value;
|
||||
buzzvm_pop(vm);
|
||||
|
||||
polygon_bound.push_back(Point(tmpx, tmpy));
|
||||
//ROS_INFO("[%i] Polygon vertex: %f, %f", buzz_utility::get_robotid(),tmpx,tmpy);
|
||||
// ROS_INFO("[%i] Polygon vertex: %f, %f", buzz_utility::get_robotid(),tmpx,tmpy);
|
||||
|
||||
buzzvm_pop(vm);
|
||||
}
|
||||
sortclose_polygon(&polygon_bound);
|
||||
|
||||
int count = buzzdict_size(t->t.value)-(Poly_vert+1);
|
||||
int count = buzzdict_size(t->t.value) - (Poly_vert + 1);
|
||||
|
||||
// Check if we are in the zone
|
||||
if (isSiteout(Point(0, 0), polygon_bound) || count < 3)
|
||||
{
|
||||
// ROS_WARN("Not in the Zone!!!");
|
||||
double goal_tmp[2];
|
||||
do
|
||||
{
|
||||
goal_tmp[0] = polygon_bound[0].x + (rand() % 100) / 100.0 * (polygon_bound[2].x - polygon_bound[0].x);
|
||||
goal_tmp[1] = polygon_bound[0].y + (rand() % 100) / 100.0 * (polygon_bound[2].y - polygon_bound[0].y);
|
||||
// ROS_WARN(" in the Zone (%f,%f)!",goal_tmp[0],goal_tmp[1]);
|
||||
} while (isSiteout(Point(goal_tmp[0], goal_tmp[1]), polygon_bound));
|
||||
ROS_WARN("Sending at a random location in the Zone (%f,%f)!", goal_tmp[0], goal_tmp[1]);
|
||||
double gps[3];
|
||||
gps_from_vec(goal_tmp, gps);
|
||||
set_gpsgoal(gps);
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
|
||||
|
||||
ROS_WARN("NP: %d, Sites: %d", Poly_vert, count);
|
||||
float *xValues = new float[count];
|
||||
float *yValues = new float[count];
|
||||
for(int32_t i = 0; i < count; ++i) {
|
||||
float* xValues = new float[count];
|
||||
float* yValues = new float[count];
|
||||
for (int32_t i = 0; i < count; ++i)
|
||||
{
|
||||
int index = i + Poly_vert;
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushi(vm, index);
|
||||
|
@ -570,122 +632,130 @@ int voronoi_center(buzzvm_t vm) {
|
|||
buzzvm_dup(vm);
|
||||
buzzvm_pushs(vm, buzzvm_string_register(vm, "x", 1));
|
||||
buzzvm_tget(vm);
|
||||
//ROS_INFO("---x-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
// ROS_INFO("---x-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
xValues[i] = buzzvm_stack_at(vm, 1)->f.value;
|
||||
buzzvm_pop(vm);
|
||||
buzzvm_dup(vm);
|
||||
buzzvm_pushs(vm, buzzvm_string_register(vm, "y", 1));
|
||||
buzzvm_tget(vm);
|
||||
//ROS_INFO("---y-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
// ROS_INFO("---y-->%f",buzzvm_stack_at(vm, 1)->f.value);
|
||||
yValues[i] = buzzvm_stack_at(vm, 1)->f.value;
|
||||
buzzvm_pop(vm);
|
||||
|
||||
buzzvm_pop(vm);
|
||||
}
|
||||
|
||||
// Check if we are in the zone
|
||||
if(isSiteout(Point(0,0), polygon_bound) || count < 3) {
|
||||
//ROS_WARN("Not in the Zone!!!");
|
||||
double goal_tmp[2];
|
||||
do{
|
||||
goal_tmp[0] = polygon_bound[0].x + (rand()%100)/100.0*(polygon_bound[2].x- polygon_bound[0].x);
|
||||
goal_tmp[1] = polygon_bound[0].y + (rand()%100)/100.0*(polygon_bound[2].y- polygon_bound[0].y);
|
||||
//ROS_WARN(" in the Zone (%f,%f)!",goal_tmp[0],goal_tmp[1]);
|
||||
} while(isSiteout(Point(goal_tmp[0],goal_tmp[1]), polygon_bound));
|
||||
ROS_WARN("Sending at a random location in the Zone (%f,%f)!",goal_tmp[0],goal_tmp[1]);
|
||||
double gps[3];
|
||||
gps_from_vec(goal_tmp, gps);
|
||||
set_gpsgoal(gps);
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
|
||||
VoronoiDiagramGenerator vdg;
|
||||
ROS_WARN("[%i] Voronoi Bounded tessellation starting with %i sites...", buzz_utility::get_robotid(),count);
|
||||
ROS_WARN("[%i] Voronoi Bounded tessellation starting with %i sites...", buzz_utility::get_robotid(), count);
|
||||
vdg.generateVoronoi(xValues, yValues, count, -dist_max, dist_max, -dist_max, dist_max, 3.0);
|
||||
if(logVoronoi) voronoicsv << ros::Time::now().toNSec() << ",";
|
||||
if (logVoronoi)
|
||||
voronoicsv << ros::Time::now().toNSec() << ",";
|
||||
vdg.resetIterator();
|
||||
//ROS_WARN("[%i] Voronoi Bounded tessellation done!", buzz_utility::get_robotid());
|
||||
// ROS_WARN("[%i] Voronoi Bounded tessellation done!", buzz_utility::get_robotid());
|
||||
|
||||
std::vector <Point>::iterator itc, next;
|
||||
for (itc = polygon_bound.begin(); itc != polygon_bound.end()-1; ++itc) {
|
||||
next = itc+1;
|
||||
if(logVoronoi) voronoicsv << itc->x << "," << itc->y << "," << next->x << "," << next->y << "," << 0 << "," << 0 << ",";
|
||||
std::vector<Point>::iterator itc, next;
|
||||
for (itc = polygon_bound.begin(); itc != polygon_bound.end() - 1; ++itc)
|
||||
{
|
||||
next = itc + 1;
|
||||
if (logVoronoi)
|
||||
voronoicsv << itc->x << "," << itc->y << "," << next->x << "," << next->y << "," << 0 << "," << 0 << ",";
|
||||
}
|
||||
|
||||
float x1,y1,x2,y2;
|
||||
float x1, y1, x2, y2;
|
||||
int s[2];
|
||||
vector <Point> cell_vert;
|
||||
vector<Point> cell_vert;
|
||||
Point Intersection;
|
||||
int i=0;
|
||||
while(vdg.getNext(x1,y1,x2,y2,s))
|
||||
int i = 0;
|
||||
while (vdg.getNext(x1, y1, x2, y2, s))
|
||||
{
|
||||
//ROS_INFO("GOT Line (%f,%f)->(%f,%f) between sites %d,%d",x1,y1,x2,y2,s[0],s[1]);
|
||||
if(sqrt((x2-x1)*(x2-x1)+(y2-y1)*(y2-y1))<0.1)
|
||||
// ROS_INFO("GOT Line (%f,%f)->(%f,%f) between sites %d,%d",x1,y1,x2,y2,s[0],s[1]);
|
||||
if (sqrt((x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1)) < 0.1)
|
||||
continue;
|
||||
bool isout1 = isSiteout(Point(x1,y1), polygon_bound);
|
||||
bool isout2 = isSiteout(Point(x2,y2), polygon_bound);
|
||||
if(isout1 && isout2){
|
||||
//ROS_INFO("Line out of area!");
|
||||
bool isout1 = isSiteout(Point(x1, y1), polygon_bound);
|
||||
bool isout2 = isSiteout(Point(x2, y2), polygon_bound);
|
||||
if (isout1 && isout2)
|
||||
{
|
||||
// ROS_INFO("Line out of area!");
|
||||
continue;
|
||||
}else if(isout1) {
|
||||
getintersection(Point(x2,y2), Point(x1,y1), polygon_bound, &Intersection);
|
||||
}
|
||||
else if (isout1)
|
||||
{
|
||||
getintersection(Point(x2, y2), Point(x1, y1), polygon_bound, &Intersection);
|
||||
x1 = Intersection.x;
|
||||
y1 = Intersection.y;
|
||||
//ROS_INFO("Site out 1 -> (%f,%f)", x1, y1);
|
||||
}else if(isout2) {
|
||||
getintersection(Point(x1,y1), Point(x2,y2), polygon_bound, &Intersection);
|
||||
// ROS_INFO("Site out 1 -> (%f,%f)", x1, y1);
|
||||
}
|
||||
else if (isout2)
|
||||
{
|
||||
getintersection(Point(x1, y1), Point(x2, y2), polygon_bound, &Intersection);
|
||||
x2 = Intersection.x;
|
||||
y2 = Intersection.y;
|
||||
//ROS_INFO("Site out 2 -> (%f,%f)", x2, y2);
|
||||
// ROS_INFO("Site out 2 -> (%f,%f)", x2, y2);
|
||||
}
|
||||
if(logVoronoi) voronoicsv << x1 << "," << y1 << "," << x2 << "," << y2 << "," << s[0] << "," << s[1] << ",";
|
||||
if (logVoronoi)
|
||||
voronoicsv << x1 << "," << y1 << "," << x2 << "," << y2 << "," << s[0] << "," << s[1] << ",";
|
||||
i++;
|
||||
if((s[0]==0 || s[1]==0)) {
|
||||
if(cell_vert.empty()){
|
||||
cell_vert.push_back(Point(x1,y1));
|
||||
cell_vert.push_back(Point(x2,y2));
|
||||
} else {
|
||||
if ((s[0] == 0 || s[1] == 0))
|
||||
{
|
||||
if (cell_vert.empty())
|
||||
{
|
||||
cell_vert.push_back(Point(x1, y1));
|
||||
cell_vert.push_back(Point(x2, y2));
|
||||
}
|
||||
else
|
||||
{
|
||||
bool alreadyin = false;
|
||||
vector <Point>::iterator itc;
|
||||
for (itc = cell_vert.begin(); itc != cell_vert.end(); ++itc) {
|
||||
vector<Point>::iterator itc;
|
||||
for (itc = cell_vert.begin(); itc != cell_vert.end(); ++itc)
|
||||
{
|
||||
double dist = sqrt((itc->x - x1) * (itc->x - x1) + (itc->y - y1) * (itc->y - y1));
|
||||
if(dist < 0.1) {
|
||||
if (dist < 0.1)
|
||||
{
|
||||
alreadyin = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if(!alreadyin)
|
||||
if (!alreadyin)
|
||||
cell_vert.push_back(Point(x1, y1));
|
||||
alreadyin = false;
|
||||
for (itc = cell_vert.begin(); itc != cell_vert.end(); ++itc) {
|
||||
for (itc = cell_vert.begin(); itc != cell_vert.end(); ++itc)
|
||||
{
|
||||
double dist = sqrt((itc->x - x2) * (itc->x - x2) + (itc->y - y2) * (itc->y - y2));
|
||||
if(dist < 0.1) {
|
||||
if (dist < 0.1)
|
||||
{
|
||||
alreadyin = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if(!alreadyin)
|
||||
if (!alreadyin)
|
||||
cell_vert.push_back(Point(x2, y2));
|
||||
}
|
||||
}
|
||||
}
|
||||
if(cell_vert.size()<3){
|
||||
ROS_WARN("[%i] Voronoi Bounded tessellation failed (%d)!", buzz_utility::get_robotid(),cell_vert.size());
|
||||
if (cell_vert.size() < 3)
|
||||
{
|
||||
ROS_WARN("[%i] Voronoi Bounded tessellation failed (%d)!", buzz_utility::get_robotid(), cell_vert.size());
|
||||
delete xValues;
|
||||
delete yValues;
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
std::sort( cell_vert.begin(), cell_vert.end(), clockwise_compare_points );
|
||||
std::sort(cell_vert.begin(), cell_vert.end(), clockwise_compare_points);
|
||||
cell_vert.push_back(cell_vert[0]);
|
||||
|
||||
double center_dist[2] = {0.0, 0.0};
|
||||
double center_dist[2] = { 0.0, 0.0 };
|
||||
polygone_center(cell_vert, center_dist);
|
||||
if(logVoronoi) voronoicsv << center_dist[0] << "," << center_dist[1] << std::endl;
|
||||
center_dist[0]/=2;
|
||||
center_dist[1]/=2;
|
||||
if (logVoronoi)
|
||||
voronoicsv << center_dist[0] << "," << center_dist[1] << std::endl;
|
||||
center_dist[0] /= 2;
|
||||
center_dist[1] /= 2;
|
||||
double gps[3];
|
||||
gps_from_vec(center_dist, gps);
|
||||
//ROS_INFO("[%i] Voronoi cell center: %f, %f, %f, %f", buzz_utility::get_robotid(), center_dist[0], center_dist[1], gps[0], gps[1]);
|
||||
// ROS_INFO("[%i] Voronoi cell center: %f, %f, %f, %f", buzz_utility::get_robotid(), center_dist[0], center_dist[1],
|
||||
// gps[0], gps[1]);
|
||||
set_gpsgoal(gps);
|
||||
|
||||
delete xValues;
|
||||
delete yValues;
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
|
||||
|
@ -769,7 +839,8 @@ int buzzuav_addNeiStatus(buzzvm_t vm)
|
|||
buzzvm_lload(vm, 1); // state table
|
||||
buzzvm_type_assert(vm, 1, BUZZTYPE_TABLE);
|
||||
buzzobj_t t = buzzvm_stack_at(vm, 1);
|
||||
if(buzzdict_size(t->t.value) != 5) {
|
||||
if (buzzdict_size(t->t.value) != 5)
|
||||
{
|
||||
ROS_ERROR("Wrong neighbor status size.");
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
|
@ -911,12 +982,17 @@ void set_gpsgoal(double goal[3])
|
|||
{
|
||||
double rb[3];
|
||||
rb_from_gps(goal, rb, cur_pos);
|
||||
if (fabs(rb[0]) < 250.0) {
|
||||
goto_gpsgoal[0] = goal[0];goto_gpsgoal[1] = goal[1];goto_gpsgoal[2] = goal[2];
|
||||
ROS_INFO("[%i] Set GPS GOAL TO ---- %f %f %f (%f %f, %f %f)", buzz_utility::get_robotid(), goal[0], goal[1], goal[2], cur_pos[0], cur_pos[1], rb[0], rb[1]);
|
||||
} else
|
||||
ROS_WARN("[%i] GPS GOAL TOO FAR !!-- %f %f %f (%f %f, %f %f)", buzz_utility::get_robotid(), goal[0], goal[1], goal[2], cur_pos[0], cur_pos[1], rb[0], rb[1]);
|
||||
|
||||
if (fabs(rb[0]) < 250.0)
|
||||
{
|
||||
goto_gpsgoal[0] = goal[0];
|
||||
goto_gpsgoal[1] = goal[1];
|
||||
goto_gpsgoal[2] = goal[2];
|
||||
ROS_INFO("[%i] Set GPS GOAL TO ---- %f %f %f (%f %f, %f %f)", buzz_utility::get_robotid(), goal[0], goal[1],
|
||||
goal[2], cur_pos[0], cur_pos[1], rb[0], rb[1]);
|
||||
}
|
||||
else
|
||||
ROS_WARN("[%i] GPS GOAL TOO FAR !!-- %f %f %f (%f %f, %f %f)", buzz_utility::get_robotid(), goal[0], goal[1],
|
||||
goal[2], cur_pos[0], cur_pos[1], rb[0], rb[1]);
|
||||
}
|
||||
|
||||
int buzzuav_arm(buzzvm_t vm)
|
||||
|
@ -987,7 +1063,7 @@ double* getgoto()
|
|||
return goto_pos;
|
||||
}
|
||||
|
||||
std::map<int, std::map<int,int>> getgrid()
|
||||
std::map<int, std::map<int, int>> getgrid()
|
||||
/*
|
||||
/ return the grid
|
||||
/-------------------------------------------------------------*/
|
||||
|
@ -1199,7 +1275,8 @@ void update_neighbors(buzzvm_t vm)
|
|||
}
|
||||
|
||||
// Clear neighbours pos
|
||||
void clear_neighbours_pos(){
|
||||
void clear_neighbours_pos()
|
||||
{
|
||||
neighbors_map.clear();
|
||||
}
|
||||
|
||||
|
|
|
@ -12,8 +12,8 @@ namespace rosbuzz_node
|
|||
{
|
||||
const string roscontroller::CAPTURE_SRV_DEFAULT_NAME = "/image_sender/capture_image";
|
||||
|
||||
roscontroller::roscontroller(ros::NodeHandle& n_c, ros::NodeHandle& n_c_priv):
|
||||
logical_clock(ros::Time()), previous_step_time(ros::Time())
|
||||
roscontroller::roscontroller(ros::NodeHandle& n_c, ros::NodeHandle& n_c_priv)
|
||||
: logical_clock(ros::Time()), previous_step_time(ros::Time())
|
||||
/*
|
||||
/ roscontroller class Constructor
|
||||
---------------*/
|
||||
|
@ -35,9 +35,9 @@ logical_clock(ros::Time()), previous_step_time(ros::Time())
|
|||
std::string fname = Compile_bzz(bzzfile_name);
|
||||
bcfname = fname + ".bo";
|
||||
dbgfname = fname + ".bdb";
|
||||
buzz_update::set_bzz_file(bzzfile_name.c_str(),debug);
|
||||
buzz_update::set_bzz_file(bzzfile_name.c_str(), debug);
|
||||
// Initialize variables
|
||||
if(setmode)
|
||||
if (setmode)
|
||||
SetMode("LOITER", 0);
|
||||
goto_pos = buzzuav_closures::getgoto();
|
||||
|
||||
|
@ -67,7 +67,7 @@ logical_clock(ros::Time()), previous_step_time(ros::Time())
|
|||
logical_clock.fromSec(0);
|
||||
logical_time_rate = 0;
|
||||
time_sync_jumped = false;
|
||||
out_msg_time=0;
|
||||
out_msg_time = 0;
|
||||
// Create log dir and open log file
|
||||
initcsvlog();
|
||||
buzzuav_closures::setWPlist(WPfile);
|
||||
|
@ -126,7 +126,7 @@ void roscontroller::RosControllerRun()
|
|||
// set ROS loop rate
|
||||
ros::Rate loop_rate(BUZZRATE);
|
||||
// check for BVMSTATE variable
|
||||
if(buzz_utility::get_bvmstate()=="Not Available")
|
||||
if (buzz_utility::get_bvmstate() == "Not Available")
|
||||
ROS_ERROR("BVMSTATE undeclared in .bzz file, please set BVMSTATE.");
|
||||
// DEBUG
|
||||
// ROS_WARN("[%i] -----------------------STARTING MAIN LOOP!", robot_id);
|
||||
|
@ -138,7 +138,8 @@ void roscontroller::RosControllerRun()
|
|||
grid_publisher();
|
||||
send_MPpayload();
|
||||
// Check updater state and step code
|
||||
if(update) buzz_update::update_routine();
|
||||
if (update)
|
||||
buzz_update::update_routine();
|
||||
if (time_step == BUZZRATE)
|
||||
{
|
||||
time_step = 0;
|
||||
|
@ -163,22 +164,25 @@ void roscontroller::RosControllerRun()
|
|||
// Call Step from buzz script
|
||||
buzz_utility::buzz_script_step();
|
||||
// Force a refresh on neighbors array once in a while
|
||||
if (timer_step >= 20*BUZZRATE){
|
||||
if (timer_step >= 20 * BUZZRATE)
|
||||
{
|
||||
clear_pos();
|
||||
timer_step = 0;
|
||||
} else
|
||||
}
|
||||
else
|
||||
timer_step++;
|
||||
// Prepare messages and publish them
|
||||
prepare_msg_and_publish();
|
||||
// Call the flight controler service
|
||||
flight_controller_service_call();
|
||||
// Broadcast local position to FCU
|
||||
if(BClpose && !setmode)
|
||||
if (BClpose && !setmode)
|
||||
SetLocalPosition(goto_pos[0], goto_pos[1], goto_pos[2], goto_pos[3]);
|
||||
// Set ROBOTS variable (swarm size)
|
||||
get_number_of_robots();
|
||||
buzz_utility::set_robot_var(no_of_robots);
|
||||
if(update) buzz_update::updates_set_robots(no_of_robots);
|
||||
if (update)
|
||||
buzz_update::updates_set_robots(no_of_robots);
|
||||
// get_xbee_status(); // commented out because it may slow down the node too much, to be tested
|
||||
|
||||
ros::spinOnce();
|
||||
|
@ -203,19 +207,19 @@ void roscontroller::initcsvlog()
|
|||
/ Create the CSV log file
|
||||
/-------------------------------------------------------*/
|
||||
{
|
||||
std::string path =
|
||||
bzzfile_name.substr(0, bzzfile_name.find_last_of("\\/")) + "/";
|
||||
path = path.substr(0, bzzfile_name.find_last_of("\\/"))+"/log/";
|
||||
std::string folder_check="mkdir -p "+path;
|
||||
std::string path = bzzfile_name.substr(0, bzzfile_name.find_last_of("\\/")) + "/";
|
||||
path = path.substr(0, bzzfile_name.find_last_of("\\/")) + "/log/";
|
||||
std::string folder_check = "mkdir -p " + path;
|
||||
system(folder_check.c_str());
|
||||
for(int i=5;i>0;i--){
|
||||
rename((path +"logger_"+ std::to_string((uint8_t)robot_id)+"_"+std::to_string(i-1)+".log").c_str(),
|
||||
(path +"logger_"+ std::to_string((uint8_t)robot_id)+"_"+std::to_string(i)+".log").c_str());
|
||||
for (int i = 5; i > 0; i--)
|
||||
{
|
||||
rename((path + "logger_" + std::to_string((uint8_t)robot_id) + "_" + std::to_string(i - 1) + ".log").c_str(),
|
||||
(path + "logger_" + std::to_string((uint8_t)robot_id) + "_" + std::to_string(i) + ".log").c_str());
|
||||
}
|
||||
path += "logger_"+std::to_string(robot_id)+"_0.log";
|
||||
path += "logger_" + std::to_string(robot_id) + "_0.log";
|
||||
log.open(path.c_str(), std::ios_base::trunc | std::ios_base::out);
|
||||
// set log data double precision
|
||||
log <<std::setprecision(15) << std::fixed;
|
||||
log << std::setprecision(15) << std::fixed;
|
||||
}
|
||||
|
||||
void roscontroller::logtocsv()
|
||||
|
@ -226,27 +230,24 @@ void roscontroller::logtocsv()
|
|||
// hardware time now
|
||||
log << ros::Time::now().toNSec() << ",";
|
||||
|
||||
log << cur_pos.latitude << "," << cur_pos.longitude << ","
|
||||
<< cur_pos.altitude << ",";
|
||||
log << cur_pos.latitude << "," << cur_pos.longitude << "," << cur_pos.altitude << ",";
|
||||
log << (int)no_of_robots << ",";
|
||||
log << neighbours_pos_map.size() << ",";
|
||||
log << (int)inmsgdata.size() << "," << message_number << ",";
|
||||
log << out_msg_time <<",";
|
||||
log << out_msg_size<<",";
|
||||
log << out_msg_time << ",";
|
||||
log << out_msg_size << ",";
|
||||
log << buzz_utility::get_bvmstate();
|
||||
|
||||
map<int, buzz_utility::Pos_struct>::iterator it =
|
||||
neighbours_pos_map.begin();
|
||||
map<int, buzz_utility::Pos_struct>::iterator it = neighbours_pos_map.begin();
|
||||
for (; it != neighbours_pos_map.end(); ++it)
|
||||
{
|
||||
log << "," << it->first << ",";
|
||||
log << (double)it->second.x << "," << (double)it->second.y
|
||||
<< "," << (double)it->second.z;
|
||||
log << (double)it->second.x << "," << (double)it->second.y << "," << (double)it->second.z;
|
||||
}
|
||||
for (std::vector<msg_data>::iterator it = inmsgdata.begin() ; it != inmsgdata.end(); ++it)
|
||||
for (std::vector<msg_data>::iterator it = inmsgdata.begin(); it != inmsgdata.end(); ++it)
|
||||
{
|
||||
log << "," << (int)it->nid << "," << (int)it->msgid << "," << (int)it->size << "," <<
|
||||
it->sent_time << ","<< it->received_time;
|
||||
log << "," << (int)it->nid << "," << (int)it->msgid << "," << (int)it->size << "," << it->sent_time << ","
|
||||
<< it->received_time;
|
||||
}
|
||||
inmsgdata.clear();
|
||||
log << std::endl;
|
||||
|
@ -395,7 +396,7 @@ void roscontroller::PubandServ(ros::NodeHandle& n_c, ros::NodeHandle& node_handl
|
|||
}
|
||||
if (node_handle.getParam("services/modeclient", topic))
|
||||
{
|
||||
if(setmode)
|
||||
if (setmode)
|
||||
mode_client = n_c.serviceClient<mavros_msgs::SetMode>(topic);
|
||||
}
|
||||
else
|
||||
|
@ -485,7 +486,6 @@ void roscontroller::Initialize_pub_sub(ros::NodeHandle& n_c, ros::NodeHandle& n_
|
|||
|
||||
capture_srv = n_c.serviceClient<mavros_msgs::CommandBool>(capture_srv_name);
|
||||
|
||||
|
||||
multi_msg = true;
|
||||
}
|
||||
|
||||
|
@ -585,9 +585,10 @@ void roscontroller::neighbours_pos_publisher()
|
|||
// std::cout<<"long obt"<<neigh_tmp.longitude<<endl;
|
||||
|
||||
// Check if any simulated target are in range
|
||||
double tf[4] = {-1, 0, 0, 0};
|
||||
double tf[4] = { -1, 0, 0, 0 };
|
||||
buzzuav_closures::check_targets_sim((it->second).x, (it->second).y, tf);
|
||||
if(tf[0]!=-1){
|
||||
if (tf[0] != -1)
|
||||
{
|
||||
buzz_utility::Pos_struct pos_tmp;
|
||||
pos_tmp.x = tf[1];
|
||||
pos_tmp.y = tf[2];
|
||||
|
@ -641,24 +642,25 @@ void roscontroller::grid_publisher()
|
|||
/ Publish current Grid from Buzz script
|
||||
/----------------------------------------------------*/
|
||||
{
|
||||
std::map<int, std::map<int,int>> grid = buzzuav_closures::getgrid();
|
||||
std::map<int, std::map<int,int>>::iterator itr = grid.begin();
|
||||
std::map<int, std::map<int, int>> grid = buzzuav_closures::getgrid();
|
||||
std::map<int, std::map<int, int>>::iterator itr = grid.begin();
|
||||
int g_w = itr->second.size();
|
||||
int g_h = grid.size();
|
||||
|
||||
if(g_w!=0 && g_h!=0) {
|
||||
if (g_w != 0 && g_h != 0)
|
||||
{
|
||||
// DEBUG
|
||||
//ROS_INFO("------> Publishing a grid of %i x %i", g_h, g_w);
|
||||
// ROS_INFO("------> Publishing a grid of %i x %i", g_h, g_w);
|
||||
auto current_time = ros::Time::now();
|
||||
nav_msgs::OccupancyGrid grid_msg;
|
||||
grid_msg.header.frame_id = "/world";
|
||||
grid_msg.header.stamp = current_time;
|
||||
grid_msg.info.map_load_time = current_time; // Same as header stamp as we do not load the map.
|
||||
grid_msg.info.resolution = 0.01;//gridMap.getResolution();
|
||||
grid_msg.info.resolution = 0.01; // gridMap.getResolution();
|
||||
grid_msg.info.width = g_w;
|
||||
grid_msg.info.height = g_h;
|
||||
grid_msg.info.origin.position.x = round(g_w/2.0) * grid_msg.info.resolution;
|
||||
grid_msg.info.origin.position.y = round(g_h/2.0) * grid_msg.info.resolution;
|
||||
grid_msg.info.origin.position.x = round(g_w / 2.0) * grid_msg.info.resolution;
|
||||
grid_msg.info.origin.position.y = round(g_h / 2.0) * grid_msg.info.resolution;
|
||||
grid_msg.info.origin.position.z = 0.0;
|
||||
grid_msg.info.origin.orientation.x = 0.0;
|
||||
grid_msg.info.origin.orientation.y = 0.0;
|
||||
|
@ -666,19 +668,21 @@ void roscontroller::grid_publisher()
|
|||
grid_msg.info.origin.orientation.w = 1.0;
|
||||
grid_msg.data.resize(g_w * g_h);
|
||||
|
||||
for (itr=grid.begin(); itr!=grid.end(); ++itr) {
|
||||
std::map<int,int>::iterator itc = itr->second.begin();
|
||||
for (itc=itr->second.begin(); itc!=itr->second.end(); ++itc) {
|
||||
grid_msg.data[(itr->first-1)*g_w+itc->first] = itc->second;
|
||||
for (itr = grid.begin(); itr != grid.end(); ++itr)
|
||||
{
|
||||
std::map<int, int>::iterator itc = itr->second.begin();
|
||||
for (itc = itr->second.begin(); itc != itr->second.end(); ++itc)
|
||||
{
|
||||
grid_msg.data[(itr->first - 1) * g_w + itc->first] = itc->second;
|
||||
// DEBUG
|
||||
//ROS_INFO("--------------> index: %i (%i,%i): %i", (itr->first-1)*g_w+itc->first, itr->first, itc->first, grid_msg.data[(itr->first-1)*g_w+itc->first]);
|
||||
// ROS_INFO("--------------> index: %i (%i,%i): %i", (itr->first-1)*g_w+itc->first, itr->first, itc->first,
|
||||
// grid_msg.data[(itr->first-1)*g_w+itc->first]);
|
||||
}
|
||||
}
|
||||
grid_pub.publish(grid_msg);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void roscontroller::Arm()
|
||||
/*
|
||||
/ Functions handling the local MAV ROS flight controller
|
||||
|
@ -729,13 +733,13 @@ with size......... | /
|
|||
else
|
||||
message_number++;
|
||||
|
||||
//header variables
|
||||
// header variables
|
||||
uint16_t tmphead[4];
|
||||
tmphead[1] = (uint16_t)message_number;
|
||||
//uint32_t stime = (uint32_t)(ros::Time::now().toSec()); //(uint32_t)(logical_clock.toSec() * 100000);
|
||||
memcpy((void*)(tmphead+2),(void*)&stime,sizeof(uint32_t));
|
||||
// uint32_t stime = (uint32_t)(ros::Time::now().toSec()); //(uint32_t)(logical_clock.toSec() * 100000);
|
||||
memcpy((void*)(tmphead + 2), (void*)&stime, sizeof(uint32_t));
|
||||
uint64_t rheader[1];
|
||||
rheader[0]=0;
|
||||
rheader[0] = 0;
|
||||
payload_out.sysid = (uint8_t)robot_id;
|
||||
payload_out.msgid = (uint32_t)message_number;
|
||||
|
||||
|
@ -755,7 +759,7 @@ with size......... | /
|
|||
{
|
||||
payload_out.payload64.push_back(payload_out_ptr[i]);
|
||||
}
|
||||
//Store out msg time
|
||||
// Store out msg time
|
||||
out_msg_time = ros::Time::now().toNSec();
|
||||
out_msg_size = out[0];
|
||||
// publish prepared messages in respective topic
|
||||
|
@ -825,7 +829,8 @@ script
|
|||
cmd_srv.request.command = buzzuav_closures::getcmd();
|
||||
if (!armstate)
|
||||
{
|
||||
if(setmode){
|
||||
if (setmode)
|
||||
{
|
||||
SetMode("LOITER", 0);
|
||||
ros::Duration(0.5).sleep();
|
||||
}
|
||||
|
@ -834,13 +839,13 @@ script
|
|||
// Registering HOME POINT.
|
||||
home = cur_pos;
|
||||
// Initialize GPS goal for safety.
|
||||
double gpspgoal[3] = {cur_pos.latitude,cur_pos.longitude,cur_pos.altitude};
|
||||
double gpspgoal[3] = { cur_pos.latitude, cur_pos.longitude, cur_pos.altitude };
|
||||
buzzuav_closures::set_gpsgoal(gpspgoal);
|
||||
BClpose = true;
|
||||
}
|
||||
if (current_mode != "GUIDED" && setmode)
|
||||
SetMode("GUIDED", 3000); // added for compatibility with 3DR Solo
|
||||
if(setmode)
|
||||
if (setmode)
|
||||
{
|
||||
if (mav_client.call(cmd_srv))
|
||||
{
|
||||
|
@ -862,7 +867,7 @@ script
|
|||
armstate = 0;
|
||||
Arm();
|
||||
}
|
||||
else if(cur_pos.altitude < 0.4) //disarm only when close to ground
|
||||
else if (cur_pos.altitude < 0.4) // disarm only when close to ground
|
||||
{
|
||||
armstate = 0;
|
||||
Arm();
|
||||
|
@ -894,17 +899,17 @@ script
|
|||
case COMPONENT_ARM_DISARM:
|
||||
if (!armstate)
|
||||
{
|
||||
if(setmode)
|
||||
if (setmode)
|
||||
SetMode("LOITER", 0);
|
||||
armstate = 1;
|
||||
Arm();
|
||||
}
|
||||
break;
|
||||
|
||||
case COMPONENT_ARM_DISARM+1:
|
||||
case COMPONENT_ARM_DISARM + 1:
|
||||
if (armstate)
|
||||
{
|
||||
if(setmode)
|
||||
if (setmode)
|
||||
SetMode("LOITER", 0);
|
||||
armstate = 0;
|
||||
Arm();
|
||||
|
@ -913,7 +918,7 @@ script
|
|||
|
||||
case NAV_SPLINE_WAYPOINT:
|
||||
goto_pos = buzzuav_closures::getgoto();
|
||||
if(setmode)
|
||||
if (setmode)
|
||||
SetLocalPosition(goto_pos[0], goto_pos[1], goto_pos[2], goto_pos[3]);
|
||||
break;
|
||||
|
||||
|
@ -950,7 +955,6 @@ void roscontroller::clear_pos()
|
|||
/Refresh neighbours Position for every ten step
|
||||
/---------------------------------------------*/
|
||||
{
|
||||
|
||||
neighbours_pos_map.clear();
|
||||
raw_neighbours_pos_map.clear();
|
||||
buzzuav_closures::clear_neighbours_pos();
|
||||
|
@ -1088,21 +1092,17 @@ void roscontroller::local_pos_callback(const geometry_msgs::PoseStamped::ConstPt
|
|||
cur_pos.x = msg->pose.position.x;
|
||||
cur_pos.y = msg->pose.position.y;
|
||||
|
||||
if(!BClpose)
|
||||
if (!BClpose)
|
||||
{
|
||||
goto_pos[0]=cur_pos.x;
|
||||
goto_pos[1]=cur_pos.y;
|
||||
goto_pos[2]=0.0;
|
||||
goto_pos[0] = cur_pos.x;
|
||||
goto_pos[1] = cur_pos.y;
|
||||
goto_pos[2] = 0.0;
|
||||
BClpose = true;
|
||||
}
|
||||
|
||||
buzzuav_closures::set_currentNEDpos(msg->pose.position.y,msg->pose.position.x);
|
||||
buzzuav_closures::set_currentNEDpos(msg->pose.position.y, msg->pose.position.x);
|
||||
// cur_pos.z = pose->pose.position.z; // Using relative altitude topic instead
|
||||
tf::Quaternion q(
|
||||
msg->pose.orientation.x,
|
||||
msg->pose.orientation.y,
|
||||
msg->pose.orientation.z,
|
||||
msg->pose.orientation.w);
|
||||
tf::Quaternion q(msg->pose.orientation.x, msg->pose.orientation.y, msg->pose.orientation.z, msg->pose.orientation.w);
|
||||
tf::Matrix3x3 m(q);
|
||||
double roll, pitch, yaw;
|
||||
m.getRPY(roll, pitch, yaw);
|
||||
|
@ -1157,7 +1157,7 @@ void roscontroller::SetLocalPosition(float x, float y, float z, float yaw)
|
|||
moveMsg.pose.orientation.w = q[3];
|
||||
|
||||
// To prevent drifting from stable position, uncomment
|
||||
//if(fabs(x)>0.005 || fabs(y)>0.005) {
|
||||
// if(fabs(x)>0.005 || fabs(y)>0.005) {
|
||||
localsetpoint_nonraw_pub.publish(moveMsg);
|
||||
//}
|
||||
}
|
||||
|
@ -1199,13 +1199,13 @@ void roscontroller::SetStreamRate(int id, int rate, int on_off)
|
|||
message.request.on_off = on_off;
|
||||
int timeout = 20; // 2sec at 10Hz
|
||||
|
||||
while (!stream_client.call(message) && timeout>0)
|
||||
while (!stream_client.call(message) && timeout > 0)
|
||||
{
|
||||
ROS_INFO("Set stream rate call failed!, trying again...");
|
||||
ros::Duration(0.1).sleep();
|
||||
timeout--;
|
||||
}
|
||||
if(timeout<1)
|
||||
if (timeout < 1)
|
||||
ROS_ERROR("Set stream rate timed out!");
|
||||
else
|
||||
ROS_WARN("Set stream rate call successful");
|
||||
|
@ -1228,12 +1228,12 @@ void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg)
|
|||
// decode msg header
|
||||
uint64_t rhead = msg->payload64[0];
|
||||
uint16_t r16head[4];
|
||||
memcpy(r16head,&rhead, sizeof(uint64_t));
|
||||
memcpy(r16head, &rhead, sizeof(uint64_t));
|
||||
uint16_t mtype = r16head[0];
|
||||
uint16_t mid = r16head[1];
|
||||
uint32_t temptime=0;
|
||||
memcpy(&temptime, r16head+2, sizeof(uint32_t));
|
||||
//float stime = (float)temptime/(float)100000;
|
||||
uint32_t temptime = 0;
|
||||
memcpy(&temptime, r16head + 2, sizeof(uint32_t));
|
||||
// float stime = (float)temptime/(float)100000;
|
||||
// if(debug) ROS_INFO("Received Msg: sent time %f for id %u",stime, mid);
|
||||
// Check for Updater message, if updater message push it into updater FIFO
|
||||
if ((uint64_t)msg->payload64[0] == (uint64_t)UPDATER_MESSAGE)
|
||||
|
@ -1284,7 +1284,7 @@ void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg)
|
|||
// Extract robot id of the neighbour
|
||||
uint16_t* out = buzz_utility::u64_cvt_u16((uint64_t) * (message_obt + index));
|
||||
// store in msg data for data log
|
||||
msg_data inm(mid,out[1],out[0]*sizeof(uint64_t),stime,ros::Time::now().toNSec());
|
||||
msg_data inm(mid, out[1], out[0] * sizeof(uint64_t), stime, ros::Time::now().toNSec());
|
||||
inmsgdata.push_back(inm);
|
||||
|
||||
if (debug)
|
||||
|
|
Loading…
Reference in New Issue