43 initialized_navdata_publishers(false),
47 last_receive_time(0.0)
64 std::string tf_prefix_key;
76 ROS_WARN(
"Changing `root_frame` has been deprecated since version 1.4. ");
81 for (
int i = 0; i < 9; i++)
83 imu_msg.linear_acceleration_covariance[i] = 0.0;
84 imu_msg.angular_velocity_covariance[i] = 0.0;
85 imu_msg.orientation_covariance[i] = 0.0;
93 ROS_WARN(
"IMU Caliberation has been deprecated since 1.4.");
133 static int freq_dev = 0;
146 ROS_INFO(
"Successfully connected to '%s' (AR-Drone %d.0 - Firmware: %s) - Battery(%%): %d",
147 ardrone_control_config.ardrone_name,
148 (IS_ARDRONE1) ? 1 : 2,
149 ardrone_control_config.num_version_soft,
151 ROS_INFO(
"Navdata Publish Settings:");
152 ROS_INFO(
" Legacy Navdata Mode: %s", enabled_legacy_navdata ?
"On" :
"Off");
156 ROS_INFO(
" Drone Navdata Send Speed: %s",
157 ardrone_application_default_config.navdata_demo == 0 ?
158 "200Hz (navdata_demo=0)" :
"15Hz (navdata_demo=1)");
161 if (ardrone_control_config.num_version_soft[0] ==
'0')
163 ROS_WARN(
"The AR-Drone has a suspicious Firmware number. It usually means the network link is unreliable.");
200 PublishNavdataTypes(navdata_raw, navdata_receive_time);
209 freq_dev = (freq_dev + 1) % 5;
214 printf(
"ROS loop terminated ... \n");
225 for (
unsigned int i = 0; i < vec.size(); i++)
229 return (ret / vec.size());
235 std::stringstream str_stream;
240 ROS_WARN(
"Covariance values for %s is not a list", param_name.c_str());
244 if (cov_list.
size() != 9)
246 ROS_WARN(
"Covariance list size for %s is not of size 9 (Size: %d)", param_name.c_str(), cov_list.
size());
249 str_stream << param_name <<
" set to [";
250 for (int32_t i = 0; i < cov_list.
size(); i++)
253 cov_array[i] =
static_cast<double>(cov_list[i]);
254 str_stream << cov_array[i] << ((i < 8) ?
", " :
"");
257 ROS_INFO(
"%s", str_stream.str().c_str());
262 ROS_INFO(
"No values found for `%s` in parameters, set all to zero.", param_name.c_str());
303 sensor_msgs::Image image_msg;
304 sensor_msgs::Image::_data_type::iterator _it;
306 if ((
cam_state == ZAP_CHANNEL_HORI) || (
cam_state == ZAP_CHANNEL_LARGE_HORI_SMALL_VERT))
310 else if ((
cam_state == ZAP_CHANNEL_VERT) || (
cam_state == ZAP_CHANNEL_LARGE_VERT_SMALL_HORI))
316 ROS_WARN_ONCE(
"Something is wrong with camera channel config.");
321 image_msg.encoding =
"rgb8";
322 image_msg.is_bigendian =
false;
331 cinfo_msg_hori.header.stamp = image_msg.header.stamp;
332 cinfo_msg_vert.header.stamp = image_msg.header.stamp;
352 image_msg.encoding =
"rgb8";
353 image_msg.is_bigendian =
false;
355 image_msg.data.clear();
357 _it = image_msg.data.begin();
362 int _e = _b + image_msg.step;
372 else if (
cam_state == ZAP_CHANNEL_LARGE_HORI_SMALL_VERT)
382 image_msg.encoding =
"rgb8";
383 image_msg.is_bigendian =
false;
385 image_msg.data.clear();
386 image_msg.data.resize((
D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH)*D1_STREAM_HEIGHT * 3);
387 _it = image_msg.data.begin();
392 int _e = _b + image_msg.step;
404 image_msg.encoding =
"rgb8";
405 image_msg.is_bigendian =
false;
406 image_msg.step = D1_MODE2_PIP_WIDTH * 3;
407 image_msg.data.clear();
409 _it = image_msg.data.begin();
414 int _e = _b + image_msg.step;
423 else if (
cam_state == ZAP_CHANNEL_LARGE_VERT_SMALL_HORI)
433 image_msg.encoding =
"rgb8";
434 image_msg.is_bigendian =
false;
436 image_msg.data.clear();
438 _it = image_msg.data.begin();
442 int _e = _b + image_msg.step;
455 image_msg.encoding =
"rgb8";
456 image_msg.is_bigendian =
false;
457 image_msg.step = D1_MODE3_PIP_WIDTH * 3;
458 image_msg.data.clear();
460 _it = image_msg.data.begin();
465 int _e = _b + image_msg.step;
483 sensor_msgs::Image image_msg;
484 sensor_msgs::Image::_data_type::iterator _it;
496 ROS_WARN_ONCE(
"Something is wrong with camera channel config.");
501 image_msg.encoding =
"rgb8";
502 image_msg.is_bigendian =
false;
511 cinfo_msg_hori.header.stamp = image_msg.header.stamp;
512 cinfo_msg_vert.header.stamp = image_msg.header.stamp;
539 if (!enabled_legacy_navdata ||
547 legacynavdata_msg.batteryPercent = navdata_raw.navdata_demo.vbat_flying_percentage;
561 legacynavdata_msg.tm = (navdata_raw.navdata_time.time & 0x001FFFFF) + (navdata_raw.navdata_time.time >> 21) * 1000000;
562 legacynavdata_msg.ax = navdata_raw.navdata_phys_measures.phys_accs[ACC_X] / 1000.0;
563 legacynavdata_msg.ay = -navdata_raw.navdata_phys_measures.phys_accs[ACC_Y] / 1000.0;
564 legacynavdata_msg.az = -navdata_raw.navdata_phys_measures.phys_accs[ACC_Z] / 1000.0;
584 legacynavdata_msg.wind_comp_angle = navdata_raw.navdata_wind_speed.wind_compensation_phi;
606 for (
int i = 0; i < navdata_raw.navdata_vision_detect.nb_detected; i++)
619 legacynavdata_msg.tags_type.push_back(navdata_raw.navdata_vision_detect.type[i]);
622 legacynavdata_msg.tags_width.push_back(navdata_raw.navdata_vision_detect.width[i]);
623 legacynavdata_msg.tags_height.push_back(navdata_raw.navdata_vision_detect.height[i]);
624 legacynavdata_msg.tags_orientation.push_back(navdata_raw.navdata_vision_detect.orientation_angle[i]);
625 legacynavdata_msg.tags_distance.push_back(navdata_raw.navdata_vision_detect.dist[i]);
630 imu_msg.header.stamp = navdata_receive_time;
644 imu_msg.angular_velocity.x = navdata_raw.navdata_phys_measures.phys_gyros[GYRO_X] * DEG_TO_RAD;
645 imu_msg.angular_velocity.y = -navdata_raw.navdata_phys_measures.phys_gyros[GYRO_Y] * DEG_TO_RAD;
646 imu_msg.angular_velocity.z = -navdata_raw.navdata_phys_measures.phys_gyros[GYRO_Z] * DEG_TO_RAD;
649 mag_msg.header.stamp = navdata_receive_time;
655 if (fabs(mag_normalizer) > 1e-9
f)
664 ROS_WARN_THROTTLE(30,
"There is something wrong with the magnetometer readings (Magnitude is extremely small).");
672 #define NAVDATA_STRUCTS_SOURCE 674 #undef NAVDATA_STRUCTS_SOURCE 689 odometry[0] += ((cos((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
690 navdata_raw.navdata_demo.vx - sin((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
691 -navdata_raw.navdata_demo.vy) * delta_t) / 1000.0;
692 odometry[1] += ((sin((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
693 navdata_raw.navdata_demo.vx + cos((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
694 -navdata_raw.navdata_demo.vy) * delta_t) / 1000.0;
698 nav_msgs::Odometry odo_msg;
699 odo_msg.header.stamp = navdata_receive_time;
700 odo_msg.header.frame_id =
"odom";
703 odo_msg.pose.pose.position.x =
odometry[0];
704 odo_msg.pose.pose.position.y =
odometry[1];
705 odo_msg.pose.pose.position.z = navdata_raw.navdata_demo.altitude / 1000.0;
707 navdata_raw.navdata_demo.phi / 180000.0 * M_PI,
708 -navdata_raw.navdata_demo.theta / 180000.0 * M_PI,
709 -navdata_raw.navdata_demo.psi / 180000.0 * M_PI);
711 odo_msg.twist.twist.linear.x = navdata_raw.navdata_demo.vx / 1000.0;
712 odo_msg.twist.twist.linear.y = -navdata_raw.navdata_demo.vy / 1000.0;
713 odo_msg.twist.twist.linear.z = -navdata_raw.navdata_demo.vz / 1000.0;
743 int main(
int argc,
char** argv)
745 C_RESULT res = C_FAIL;
746 char * drone_ip_address = NULL;
768 while (argc && *argv[0] ==
'-')
770 if (!strcmp(*argv,
"-ip") && (argc > 1))
772 drone_ip_address = *(argv + 1);
773 printf(
"Using custom ip address %s\n", drone_ip_address);
782 vp_com_wifi_config_t *config =
reinterpret_cast<vp_com_wifi_config_t*
>(wifi_config());
786 vp_os_memset(&wifi_ardrone_ip[0], 0, ARDRONE_IPADDRESS_SIZE);
789 if (drone_ip_address)
791 printf(
"===================+> %s\n", drone_ip_address);
792 strncpy(&wifi_ardrone_ip[0], drone_ip_address, ARDRONE_IPADDRESS_SIZE - 1);
796 printf(
"===================+> %s\n", config->server);
797 strncpy(&wifi_ardrone_ip[0], config->server, ARDRONE_IPADDRESS_SIZE - 1);
801 while (-1 == getDroneVersion(
".", wifi_ardrone_ip, &ardroneVersion))
803 printf(
"Getting AR.Drone version ...\n");
808 res = ardrone_tool_setup_com(NULL);
811 PRINT(
"Wifi initialization failed. It means either:\n");
812 PRINT(
"\t* you're not root (it's mandatory because you can set up wifi connection only as root)\n");
813 PRINT(
"\t* wifi device is not present (on your pc or on your card)\n");
814 PRINT(
"\t* you set the wrong name for wifi interface (for example rausb0 instead of wlan0) \n");
815 PRINT(
"\t* ap is not up (reboot card or remove wifi usb dongle)\n");
816 PRINT(
"\t* wifi device has no antenna\n");
821 const char* appname =
reinterpret_cast<const char*
>(
DRIVER_APPNAME);
823 ardrone_gen_appid(appname,
"2.0", app_id, app_name, APPLI_NAME_SIZE);
824 ardrone_gen_usrid(usrname, usr_id, usr_name, USER_NAME_SIZE);
829 res = ardrone_tool_init(wifi_ardrone_ip,
830 strlen(wifi_ardrone_ip),
836 MAX_FLIGHT_STORING_SIZE,
841 res = ardrone_tool_update();
843 res = ardrone_tool_shutdown();
static double CalcAverage(const std::vector< double > &vec)
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
bool SetCamChannelCallback(ardrone_autonomy::CamSelect::Request &request, ardrone_autonomy::CamSelect::Response &response)
ros::Subscriber takeoff_sub
bool_t ardrone_tool_exit()
std::string drone_frame_id
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
camera_info_manager::CameraInfoManager * cinfo_hori
camera_info_manager::CameraInfoManager * cinfo_vert
#define ROS_WARN_THROTTLE(rate,...)
ros::Publisher navdata_pub
sensor_msgs::CameraInfo getCameraInfo(void)
int32_t current_navdata_id
void publish(const boost::shared_ptr< M > &message) const
tf::StampedTransform tf_base_front
ros::Time shared_video_receive_time
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber reset_sub
void CmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
uint32_t getNumSubscribers() const
#define D1_MODE3_PIP_HEIGHT
int32_t copy_current_navdata_id
vp_os_mutex_t navdata_lock
char buffer[MULTICONFIG_ID_SIZE+1]
tf::TransformBroadcaster tf_broad
image_transport::CameraPublisher vert_pub
bool SetLedAnimationCallback(ardrone_autonomy::LedAnim::Request &request, ardrone_autonomy::LedAnim::Response &response)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void PublishOdometry(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
image_transport::CameraPublisher hori_pub
video_decoder_config_t vec
int main(int argc, char **argv)
bool ToggleCamCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const navdata_unpacked_t * shared_raw_navdata_ptr
Type const & getType() const
image_transport::CameraPublisher image_pub
#define D1_MODE3_PIP_WIDTH
int32_t copy_current_frame_id
ardrone_autonomy::Navdata legacynavdata_msg
void LandCallback(const std_msgs::Empty &msg)
bool SetRecordCallback(ardrone_autonomy::RecordEnable::Request &request, ardrone_autonomy::RecordEnable::Response &response)
std::string resolve(const std::string &prefix, const std::string &frame_name)
ros::Time last_receive_time
bool FlatTrimCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
std::string drone_frame_base
void ResetCallback(const std_msgs::Empty &msg)
tf::StampedTransform tf_base_bottom
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
#define ROS_WARN_ONCE(...)
tf::StampedTransform tf_odom
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define D1_VERTSTREAM_HEIGHT
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
ros::ServiceServer flat_trim_srv
ros::ServiceServer set_cam_channel_srv
ros::ServiceServer toggle_cam_srv
ros::ServiceServer set_flight_anim_srv
static bool ReadCovParams(const std::string ¶m_name, boost::array< double, 9 > &cov_array)
bool SetFlightAnimationCallback(ardrone_autonomy::FlightAnim::Request &request, ardrone_autonomy::FlightAnim::Response &response)
#define ROS_DEBUG_STREAM(args)
printf("Deleting Profile %s\n", buffer)
ros::Time shared_navdata_receive_time
#define D1_MODE2_PIP_HEIGHT
void TakeoffCallback(const std_msgs::Empty &msg)
ros::ServiceServer set_record_srv
uint32_t getNumSubscribers() const
std::string drone_frame_imu
ros::ServiceServer set_led_animation_srv
#define D1_MODE2_PIP_WIDTH
void ControlCHandler(int signal)
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
std::string drone_frame_front_cam
ROSCPP_DECL void shutdown()
ros::NodeHandle private_nh
bool hasParam(const std::string &key) const
#define D1_VERTSTREAM_WIDTH
ros::NodeHandle node_handle
ROSCPP_DECL void spinOnce()
geometry_msgs::Vector3Stamped mag_msg
ros::Subscriber cmd_vel_sub
void PublishNavdata(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
std::string drone_frame_bottom_cam