Untabification and Added get functions for Xbee_status
This commit is contained in:
parent
1d24de28a5
commit
8e5acd264d
|
@ -42,9 +42,11 @@
|
|||
|
||||
using namespace std;
|
||||
|
||||
namespace rosbzz_node{
|
||||
namespace rosbzz_node
|
||||
{
|
||||
|
||||
class roscontroller{
|
||||
class roscontroller
|
||||
{
|
||||
|
||||
public:
|
||||
roscontroller(ros::NodeHandle& n_c, ros::NodeHandle& n_c_priv);
|
||||
|
@ -56,18 +58,17 @@ private:
|
|||
struct num_robot_count
|
||||
{
|
||||
uint8_t history[10];
|
||||
uint8_t index=0;
|
||||
uint8_t current=0;
|
||||
uint8_t index = 0;
|
||||
uint8_t current = 0;
|
||||
num_robot_count(){}
|
||||
|
||||
}; typedef struct num_robot_count Num_robot_count ;
|
||||
}; typedef struct num_robot_count Num_robot_count ; // not useful in cpp
|
||||
|
||||
struct gps
|
||||
{
|
||||
double longitude=0.0;
|
||||
double latitude=0.0;
|
||||
float altitude=0.0;
|
||||
}; typedef struct gps GPS ;
|
||||
}; typedef struct gps GPS ; // not useful in cpp
|
||||
|
||||
GPS target, home, cur_pos;
|
||||
double cur_rel_altitude;
|
||||
|
@ -88,7 +89,7 @@ private:
|
|||
uint8_t no_of_robots=0;
|
||||
/*tmp to be corrected*/
|
||||
uint8_t no_cnt=0;
|
||||
uint8_t old_val=0;
|
||||
uint8_t old_val=0 ;
|
||||
std::string bzzfile_name, fcclient_name, armclient, modeclient, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by,xbeesrv_name, setpoint_name;
|
||||
std::string stream_client_name;
|
||||
std::string relative_altitude_sub_name;
|
||||
|
@ -178,7 +179,7 @@ private:
|
|||
double gps_t_lon, double gps_t_lat,
|
||||
double gps_r_lon, double gps_r_lat);
|
||||
|
||||
/*battery status callback*/
|
||||
/*battery status callback */
|
||||
void battery(const mavros_msgs::BatteryStatus::ConstPtr& msg);
|
||||
|
||||
/*flight extended status callback*/
|
||||
|
@ -232,7 +233,15 @@ private:
|
|||
void SetStreamRate(int id, int rate, int on_off);
|
||||
|
||||
void get_number_of_robots();
|
||||
|
||||
void GetRobotId();
|
||||
bool GetDequeFull(bool &result);
|
||||
bool GetRssi(float &result);
|
||||
bool TriggerAPIRssi(const uint8_t short_id);
|
||||
bool GetAPIRssi(const uint8_t short_id, float &result);
|
||||
bool GetRawPacketLoss(const uint8_t short_id, float &result);
|
||||
bool GetFilteredPacketLoss(const uint8_t short_id, float &result);
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -414,7 +414,7 @@ int create_stig_tables() {
|
|||
//buzzvm_gstore(VM);
|
||||
//buzzvm_dump(VM);
|
||||
|
||||
/*buzzvm_pushs(VM, buzzvm_string_register(VM, "vt", 1));
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "vt", 1));
|
||||
buzzvm_gload(VM);
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "put", 1));
|
||||
buzzvm_tget(VM);
|
||||
|
@ -785,5 +785,3 @@ int create_stig_tables() {
|
|||
buzzvm_gstore(VM);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -18,13 +18,13 @@ namespace buzzuav_closures{
|
|||
static double goto_pos[3];
|
||||
static double rc_goto_pos[3];
|
||||
static float batt[3];
|
||||
static float obst[5]={0,0,0,0,0};
|
||||
static float obst[5] = {0,0,0,0,0};
|
||||
static double cur_pos[3];
|
||||
static uint8_t status;
|
||||
static int cur_cmd = 0;
|
||||
static int rc_cmd=0;
|
||||
static int buzz_cmd=0;
|
||||
static float height=0;
|
||||
static int rc_cmd = 0;
|
||||
static int buzz_cmd = 0;
|
||||
static float height = 0;
|
||||
|
||||
|
||||
std::map< int, buzz_utility::Pos_struct> neighbors_map;
|
||||
|
@ -32,15 +32,18 @@ namespace buzzuav_closures{
|
|||
/****************************************/
|
||||
/****************************************/
|
||||
|
||||
int buzzros_print(buzzvm_t vm) {
|
||||
int buzzros_print(buzzvm_t vm)
|
||||
{
|
||||
int i;
|
||||
char buffer [50] = "";
|
||||
sprintf(buffer,"%s [%i]", buffer, (int)buzz_utility::get_robotid());
|
||||
for(i = 1; i < buzzdarray_size(vm->lsyms->syms); ++i) {
|
||||
for(i = 1; i < buzzdarray_size(vm->lsyms->syms); ++i)
|
||||
{
|
||||
buzzvm_lload(vm, i);
|
||||
buzzobj_t o = buzzvm_stack_at(vm, 1);
|
||||
buzzvm_pop(vm);
|
||||
switch(o->o.type) {
|
||||
switch(o->o.type)
|
||||
{
|
||||
case BUZZTYPE_NIL:
|
||||
sprintf(buffer,"%s BUZZ - [nil]", buffer);
|
||||
break;
|
||||
|
@ -70,7 +73,7 @@ namespace buzzuav_closures{
|
|||
break;
|
||||
}
|
||||
}
|
||||
ROS_INFO(buffer);
|
||||
ROS_INFO("%s",buffer);
|
||||
//fprintf(stdout, "\n");
|
||||
return buzzvm_ret0(vm);
|
||||
}
|
||||
|
@ -107,7 +110,8 @@ namespace buzzuav_closures{
|
|||
/*----------------------------------------/
|
||||
/ Buzz closure to move following a 2D vector
|
||||
/----------------------------------------*/
|
||||
int buzzuav_moveto(buzzvm_t vm) {
|
||||
int buzzuav_moveto(buzzvm_t vm)
|
||||
{
|
||||
buzzvm_lnum_assert(vm, 2);
|
||||
buzzvm_lload(vm, 1); /* dx */
|
||||
buzzvm_lload(vm, 2); /* dy */
|
||||
|
@ -117,7 +121,8 @@ namespace buzzuav_closures{
|
|||
buzzvm_type_assert(vm, 1, BUZZTYPE_FLOAT);
|
||||
float dy = buzzvm_stack_at(vm, 1)->f.value;
|
||||
float dx = buzzvm_stack_at(vm, 2)->f.value;
|
||||
double d = sqrt(dx*dx+dy*dy); //range
|
||||
// The compiler warnings are useful!
|
||||
// double d = sqrt(dx*dx+dy*dy); //range
|
||||
goto_pos[0]=dx;
|
||||
goto_pos[1]=dy;
|
||||
goto_pos[2]=height;
|
||||
|
|
File diff suppressed because it is too large
Load Diff
Loading…
Reference in New Issue