diff --git a/include/roscontroller.h b/include/roscontroller.h index eb9d1b5..ee44f0b 100644 --- a/include/roscontroller.h +++ b/include/roscontroller.h @@ -86,10 +86,10 @@ private: double longitude, double altitude); /*convert from cartesian to spherical coordinate system callback */ - double* cvt_spherical_coordinates(double neighbours_pos_payload []); + void cvt_spherical_coordinates(double neighbours_pos_payload [], double out[]); /*convert from spherical to cartesian coordinate system callback */ - double* cvt_cartesian_coordinates(double neighbours_pos_payload []); + void cvt_cartesian_coordinates(double neighbours_pos_payload [], double out[]); /*battery status callback*/ void battery(const mavros_msgs::BatteryStatus::ConstPtr& msg); diff --git a/launch/rosbuzzm100.launch b/launch/rosbuzzm100.launch index 4af488e..0c5c75c 100644 --- a/launch/rosbuzzm100.launch +++ b/launch/rosbuzzm100.launch @@ -2,7 +2,7 @@ - + diff --git a/src/buzzuav_closures.cpp b/src/buzzuav_closures.cpp index 5cd8aaf..a743bbb 100644 --- a/src/buzzuav_closures.cpp +++ b/src/buzzuav_closures.cpp @@ -63,16 +63,21 @@ int buzzros_print(buzzvm_t vm) { /****************************************/ int buzzuav_goto(buzzvm_t vm) { - buzzvm_lnum_assert(vm, 3); - buzzvm_lload(vm, 1); /* Altitude */ - buzzvm_lload(vm, 2); /* Longitude */ - buzzvm_lload(vm, 3); /* Latitude */ - buzzvm_type_assert(vm, 3, BUZZTYPE_FLOAT); + buzzvm_lnum_assert(vm, 2); + buzzvm_lload(vm, 1); /* dx */ + buzzvm_lload(vm, 2); /* dy */ + //buzzvm_lload(vm, 3); /* Latitude */ + //buzzvm_type_assert(vm, 3, BUZZTYPE_FLOAT); buzzvm_type_assert(vm, 2, BUZZTYPE_FLOAT); buzzvm_type_assert(vm, 1, BUZZTYPE_FLOAT); - goto_pos[2]=buzzvm_stack_at(vm, 1)->f.value; - goto_pos[1]=buzzvm_stack_at(vm, 2)->f.value; - goto_pos[0]=buzzvm_stack_at(vm, 3)->f.value; + float dy = buzzvm_stack_at(vm, 1)->f.value; + float dx = buzzvm_stack_at(vm, 2)->f.value; + //goto_pos[0]=buzzvm_stack_at(vm, 3)->f.value; + double dlat=dx/(6371000+cur_pos[2]); + double dlon=dy/cos(cur_pos[0]/180*3.1416)/(6371000+cur_pos[2]); + goto_pos[0]=cur_pos[0]+dlat*180/3.1416; + goto_pos[1]=cur_pos[1]+dlon*180/3.1416; + goto_pos[2]=cur_pos[2]; cur_cmd=mavros_msgs::CommandCode::NAV_WAYPOINT; printf(" Buzz requested Go To, to Latitude: %15f , Longitude: %15f, Altitude: %15f \n",goto_pos[0],goto_pos[1],goto_pos[2]); buzz_cmd=2; diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 33d4fa6..1e51ce5 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -247,36 +247,33 @@ namespace rosbzz_node{ } /*convert from spherical to cartesian coordinate system callback */ - double* roscontroller::cvt_cartesian_coordinates(double neighbours_pos_payload []){ + void roscontroller::cvt_cartesian_coordinates(double spherical_pos_payload [], double out[]){ double latitude, longitude, rho; - latitude=neighbours_pos_payload[0]; - longitude = neighbours_pos_payload[1]; - rho=neighbours_pos_payload[2]+6371000; //centered on Earth + latitude = spherical_pos_payload[0] / 180 * 3.1416; + longitude = spherical_pos_payload[1] / 180 * 3.1416; + rho = spherical_pos_payload[2]+6371000; //centered on Earth try { - neighbours_pos_payload[0] = cos(latitude) * cos(longitude) * rho; - neighbours_pos_payload[1] = cos(latitude) * sin(longitude) * rho; - neighbours_pos_payload[2] = sin(latitude) * rho; // z is 'up' + out[0] = cos(latitude) * cos(longitude) * rho; + out[1] = cos(latitude) * sin(longitude) * rho; + out[2] = sin(latitude) * rho; // z is 'up' } catch (std::overflow_error e) { std::cout << e.what() << " Error in convertion to cartesian coordinate system "< ..." include "/home/ubuntu/buzz/src/include/vec2.bzz"