diff --git a/.gitignore b/.gitignore index 64f22eb..f426dc9 100644 --- a/.gitignore +++ b/.gitignore @@ -5,3 +5,4 @@ src/test* *.bo *.bdb *.bdbg +buzz_scripts/log* diff --git a/buzz_scripts/graphform.bzz b/buzz_scripts/graphform.bzz index 7382af9..2bcdd30 100644 --- a/buzz_scripts/graphform.bzz +++ b/buzz_scripts/graphform.bzz @@ -4,9 +4,10 @@ include "string.bzz" include "vec2.bzz" include "update.bzz" -include "barrier.bzz" # don't use a stigmergy id=11 with this header. + +include "vstigenv.bzz" # reserve stigmergy id=20 and 21 for this header. +include "barrier.bzz" # reserve stigmergy id=11 for this header. include "uavstates.bzz" # require an 'action' function to be defined here. -include "vstigenv.bzz" include "graphs/shapes_Y.bzz" @@ -88,7 +89,7 @@ m_fTargetDistanceTolerance=0 #step cunt step_cunt=0 -#virtual stigmergy +# virtual stigmergy for the LOCK barrier. m_lockstig = 1 # Lennard-Jones parameters, may need change @@ -101,24 +102,6 @@ function FlockInteraction(dist,target,epsilon){ return mag } -function LimitAngle(angle){ - if(angle>2*math.pi) - return angle-2*math.pi - else if (angle<0) - return angle+2*math.pi - else - return angle -} - -# -# Calculates the angle of the given vector2. -# PARAM v: The vector2. -# RETURN: The angle of the vector. -# -Angle = function(v) { - return math.atan(v.y, v.x) -} - # #return the number of value in table # @@ -205,20 +188,6 @@ function find(table,value){ return index } -function pow(base,exponent){ - var i=0 - var renturn_val=1 - if(exponent==0) - return 1 - else{ - while(i::iterator it = + neighbours_pos_map.begin(); + log << neighbours_pos_map.size()<< ","; + for (; it != neighbours_pos_map.end(); ++it) + { + log << (double)it->second.x << "," << (double)it->second.y + << "," << (double)it->second.z << ","; + } + const uint8_t shrt_id= 0xFF; + float result; + if ( GetAPIRssi(shrt_id, result) ) + log<second.x << "," << (double)it->second.y << "," << (double)it->second.z; } - log << std::endl; + log << std::endl;*/ } /*Set ROBOTS variable for barrier in .bzz from neighbours count*/ // no_of_robots=get_number_of_robots(); get_number_of_robots(); buzz_utility::set_robot_var(no_of_robots); + /*Retrive the state of the graph and uav and log TODO WARNING :PLEASE REMOVE IF + SCRIPT IS NOT graphform.bzz*/ + static buzzvm_t VM = buzz_utility::get_vm(); + buzzvm_pushs(VM, buzzvm_string_register(VM, "m_eState",1)); + buzzvm_gload(VM); + buzzobj_t graph_state = buzzvm_stack_at(VM, 1); + buzzvm_pop(VM); + std::stringstream state_buff; + state_buff<< graph_state->s.value.str<<","; + buzzvm_pushs(VM, buzzvm_string_register(VM, "UAVSTATE",1)); + buzzvm_gload(VM); + buzzobj_t uav_state = buzzvm_stack_at(VM, 1); + buzzvm_pop(VM); + state_buff<< uav_state->s.value.str; + log<0) no_of_robots // =neighbours_pos_map.size()+1; // buzz_utility::set_robot_var(no_of_robots); @@ -337,7 +389,7 @@ void roscontroller::GetSubscriptionParameters(ros::NodeHandle &node_handle) std::string battery_topic; node_handle.getParam("topics/battery", battery_topic); - m_smTopic_infos.insert(pair(battery_topic, "mavros_msgs/BatteryStatus")); + m_smTopic_infos.insert(pair(battery_topic, "mavros_msgs/BatteryState")); std::string status_topic; node_handle.getParam("topics/status", status_topic); @@ -439,9 +491,9 @@ void roscontroller::Subscribe(ros::NodeHandle &n_c) m_smTopic_infos.begin(); it != m_smTopic_infos.end(); ++it) { if (it->second == "mavros_msgs/ExtendedState") { - flight_estatus_sub = n_c.subscribe(it->first, 5, &roscontroller::flight_extended_status_update, this); + flight_status_sub = n_c.subscribe(it->first, 100, &roscontroller::flight_extended_status_update, this); } else if (it->second == "mavros_msgs/State") { - flight_status_sub = n_c.subscribe(it->first, 5, &roscontroller::flight_status_update, this); + flight_status_sub = n_c.subscribe(it->first, 100, &roscontroller::flight_status_update, this); } else if (it->second == "mavros_msgs/BatteryStatus") { battery_sub = n_c.subscribe(it->first, 5, &roscontroller::battery, this); } else if (it->second == "sensor_msgs/NavSatFix") { @@ -459,17 +511,31 @@ void roscontroller::Subscribe(ros::NodeHandle &n_c) /-------------------------------------------------------*/ std::string roscontroller::Compile_bzz(std::string bzzfile_name) { + /*TODO: change to bzzc instead of bzzparse and also add -I for includes*/ /*Compile the buzz code .bzz to .bo*/ stringstream bzzfile_in_compile; std::string path = bzzfile_name.substr(0, bzzfile_name.find_last_of("\\/")) + "/"; + // bzzfile_in_compile << path << "/"; + // path = bzzfile_in_compile.str(); + // bzzfile_in_compile.str(""); std::string name = bzzfile_name.substr(bzzfile_name.find_last_of("/\\") + 1); name = name.substr(0, name.find_last_of(".")); bzzfile_in_compile << "bzzc -I " << path - << "include/"; + << "include/"; //<<" "<