merge with field changes
This commit is contained in:
commit
e5aa343648
@ -69,9 +69,9 @@ private:
|
||||
double DEFAULT_REFERENCE_LATITUDE = 45.457817;
|
||||
double DEFAULT_REFERENCE_LONGITUDE = -73.636075;
|
||||
|
||||
double target[3];
|
||||
double cur_pos[3];
|
||||
double home[3];
|
||||
double target[3];
|
||||
double cur_rel_altitude;
|
||||
uint64_t payload;
|
||||
std::map< int, buzz_utility::Pos_struct> neighbours_pos_map;
|
||||
|
@ -15,8 +15,8 @@ TARGET_ALTITUDE = 3.0
|
||||
CURSTATE = "TURNEDOFF"
|
||||
|
||||
# Lennard-Jones parameters
|
||||
TARGET = 10.0 #0.000001001
|
||||
EPSILON = 18.0 #0.001
|
||||
TARGET = 12.0 #0.000001001
|
||||
EPSILON = 6.0 #0.001
|
||||
|
||||
# Lennard-Jones interaction magnitude
|
||||
function lj_magnitude(dist, target, epsilon) {
|
||||
@ -48,9 +48,12 @@ function hexagon() {
|
||||
# if(timeW>=WAIT_TIMEOUT) { #FOR MOVETO TESTS
|
||||
# timeW =0
|
||||
# statef=land
|
||||
# } else if(timeW>=WAIT_TIMEOUT/2) {
|
||||
# timeW = timeW+1
|
||||
# uav_moveto(0.06,0.0)
|
||||
# } else {
|
||||
# timeW = timeW+1
|
||||
# uav_moveto(0.0,0.0)
|
||||
# uav_moveto(0.0,0.06)
|
||||
# }
|
||||
}
|
||||
|
||||
|
@ -35,7 +35,6 @@ namespace rosbzz_node{
|
||||
robot_id= strtol(robot_name.c_str() + 5, NULL, 10);
|
||||
setpoint_counter = 0;
|
||||
fcu_timeout = TIMEOUT;
|
||||
|
||||
}
|
||||
|
||||
/*---------------------
|
||||
@ -754,8 +753,8 @@ namespace rosbzz_node{
|
||||
// ROS_INFO("[%i] ROSBuzz Home: %.7f, %.7f", robot_id, home[0], home[1]);
|
||||
// ROS_INFO("[%i] ROSBuzz LocalPos: %.7f, %.7f", robot_id, local_pos[0], local_pos[1]);
|
||||
|
||||
/*prepare the goto publish message ATTENTION: ENU FRAME FOR MAVROS STANDARD (then converted to NED)*/
|
||||
target[0]+=y; target[1]+=x;
|
||||
/*prepare the goto publish message ATTENTION: ENU FRAME FOR MAVROS STANDARD (then converted to NED)*/
|
||||
target[0]+=y; target[1]+=x;
|
||||
moveMsg.pose.position.x = target[0];//local_pos[1]+y;
|
||||
moveMsg.pose.position.y = target[1];//local_pos[0]+x;
|
||||
moveMsg.pose.position.z = z;
|
||||
|
Loading…
Reference in New Issue
Block a user