moved BVM state publisher to buzz_utility
This commit is contained in:
parent
de64825561
commit
3bab2e5f7b
@ -77,4 +77,6 @@ buzzvm_t get_vm();
|
|||||||
void set_robot_var(int ROBOTS);
|
void set_robot_var(int ROBOTS);
|
||||||
|
|
||||||
int get_inmsg_size();
|
int get_inmsg_size();
|
||||||
|
|
||||||
|
std::string getuavstate();
|
||||||
}
|
}
|
||||||
|
@ -98,10 +98,7 @@ double* getgoto();
|
|||||||
* returns the current grid
|
* returns the current grid
|
||||||
*/
|
*/
|
||||||
std::map<int, std::map<int,int>> getgrid();
|
std::map<int, std::map<int,int>> getgrid();
|
||||||
/*
|
|
||||||
* returns the current Buzz state
|
|
||||||
*/
|
|
||||||
std::string getuavstate();
|
|
||||||
/*
|
/*
|
||||||
* returns the gimbal commands
|
* returns the gimbal commands
|
||||||
*/
|
*/
|
||||||
|
@ -564,4 +564,19 @@ int get_inmsg_size()
|
|||||||
{
|
{
|
||||||
return IN_MSG.size();
|
return IN_MSG.size();
|
||||||
}
|
}
|
||||||
|
string getuavstate()
|
||||||
|
/*
|
||||||
|
/ return current BVM state
|
||||||
|
---------------------------------------*/
|
||||||
|
{
|
||||||
|
std::string uav_state = "Unknown";
|
||||||
|
if(VM && VM->strings){
|
||||||
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "BVMSTATE", 1));
|
||||||
|
buzzvm_gload(VM);
|
||||||
|
buzzobj_t obj = buzzvm_stack_at(VM, 1);
|
||||||
|
uav_state = string(obj->s.value.str);
|
||||||
|
buzzvm_pop(VM);
|
||||||
|
}
|
||||||
|
return uav_state;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
@ -479,19 +479,6 @@ float* getgimbal()
|
|||||||
return rc_gimbal;
|
return rc_gimbal;
|
||||||
}
|
}
|
||||||
|
|
||||||
string getuavstate()
|
|
||||||
/*
|
|
||||||
/ return current BVM state
|
|
||||||
---------------------------------------*/
|
|
||||||
{
|
|
||||||
static buzzvm_t VM = buzz_utility::get_vm();
|
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "BVMSTATE", 1));
|
|
||||||
buzzvm_gload(VM);
|
|
||||||
buzzobj_t uav_state = buzzvm_stack_at(VM, 1);
|
|
||||||
buzzvm_pop(VM);
|
|
||||||
return uav_state->s.value.str;
|
|
||||||
}
|
|
||||||
|
|
||||||
int getcmd()
|
int getcmd()
|
||||||
/*
|
/*
|
||||||
/ return current mavros command to the FC
|
/ return current mavros command to the FC
|
||||||
|
@ -475,7 +475,7 @@ void roscontroller::uavstate_publisher()
|
|||||||
/----------------------------------------------------*/
|
/----------------------------------------------------*/
|
||||||
{
|
{
|
||||||
std_msgs::String uavstate_msg;
|
std_msgs::String uavstate_msg;
|
||||||
uavstate_msg.data = buzzuav_closures::getuavstate();
|
uavstate_msg.data = buzz_utility::getuavstate();
|
||||||
uavstate_pub.publish(uavstate_msg);
|
uavstate_pub.publish(uavstate_msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user