SiftNode::SiftNode() : _it(_node) { ros::NodeHandle pnh("~"); pnh.param("use_mask", _useMask, false); _pubFeatures = _node.advertise<posedetection_msgs::Feature0D>("Feature0D",1); _pubSift = _node.advertise<posedetection_msgs::ImageFeature0D>("ImageFeature0D",1); _srvDetect = _node.advertiseService("Feature0DDetect",&SiftNode::detectCb,this); if (!_useMask) { _subImage = _it.subscribe("image",1,&SiftNode::imageCb,this); } else { _subImageWithMask.reset(new image_transport::SubscriberFilter(_it, "image", 1)); _subMask.reset(new image_transport::SubscriberFilter(_it, "mask", 1)); _sync.reset(new message_filters::Synchronizer<SyncPolicy>(SyncPolicy(100), *_subImageWithMask, *_subMask)); _sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2)); } _subInfo = _node.subscribe("camera_info",1,&SiftNode::infoCb,this); lasttime = ros::Time::now(); _bInfoInitialized = false; }
FlyerInterface::FlyerInterface(ros::NodeHandle nh, ros::NodeHandle nh_private): nh_(nh), nh_private_(nh_private), cfg_ctrl_srv_(ros::NodeHandle(nh_private_, "ctrl")), cfg_x_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_x")), cfg_y_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_y")), cfg_z_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_z")), cfg_vx_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_vx")), cfg_vy_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_vy")), cfg_vz_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_vz")), cfg_yaw_srv_(ros::NodeHandle(nh_private_, "ctrl/pid_yaw")), cfg_comm_srv_(ros::NodeHandle(nh_private_, "comm")), connected_(false) { ROS_INFO("Starting FlyerInterface"); ros::NodeHandle nh_mav (nh_, "mav"); // **** initialize vaiables cmd_roll_ = 0.0; cmd_pitch_ = 0.0; cmd_yaw_rate_ = 0.0; cmd_thrust_ = 0.0; cpu_load_index_ = 0; cpu_loads_.resize(50); // **** get parameters initializeParams(); // **** dynamic reconfigure services CfgZServer::CallbackType f1 = boost::bind(&FlyerInterface::reconfig_z_callback, this, _1, _2); cfg_z_srv_.setCallback(f1); CfgXServer::CallbackType f2 = boost::bind(&FlyerInterface::reconfig_x_callback, this, _1, _2); cfg_x_srv_.setCallback(f2); CfgYServer::CallbackType f3 = boost::bind(&FlyerInterface::reconfig_y_callback, this, _1, _2); cfg_y_srv_.setCallback(f3); CfgYawServer::CallbackType f4 = boost::bind(&FlyerInterface::reconfig_yaw_callback, this, _1, _2); cfg_yaw_srv_.setCallback(f4); CfgCommServer::CallbackType f5 = boost::bind(&FlyerInterface::reconfig_comm_callback, this, _1, _2); cfg_comm_srv_.setCallback(f5); CfgCtrlServer::CallbackType f6 = boost::bind(&FlyerInterface::reconfig_ctrl_callback, this, _1, _2); cfg_ctrl_srv_.setCallback(f6); CfgVXServer::CallbackType f7 = boost::bind(&FlyerInterface::reconfig_vx_callback, this, _1, _2); cfg_vx_srv_.setCallback(f7); CfgVYServer::CallbackType f8 = boost::bind(&FlyerInterface::reconfig_vy_callback, this, _1, _2); cfg_vy_srv_.setCallback(f8); CfgVZServer::CallbackType f9 = boost::bind(&FlyerInterface::reconfig_vz_callback, this, _1, _2); cfg_vz_srv_.setCallback(f9); // **** connect connected_ = comm_.connect(serial_port_rx_, serial_port_tx_, baudrate_); if (!connected_) { ROS_ERROR("unable to connect"); return; } // **** configure sendCommConfig(); sendKFConfig(true); // configure and reset to 0 state sendPIDConfig(); sendCtrlConfig(); // *** register publishers if (publish_pose_) { pose_publisher_ = nh_mav.advertise<geometry_msgs::PoseStamped>( "pose", 10); } vel_publisher_ = nh_mav.advertise<geometry_msgs::TwistStamped>( "vel", 10); imu_publisher_ = nh_mav.advertise<sensor_msgs::Imu>( "imu", 10); flight_state_publisher_ = nh_mav.advertise<std_msgs::UInt8>( "status/flight_state", 1); battery_voltage_publisher_ = nh_mav.advertise<std_msgs::Float32>( "status/battery_voltage", 1); cpu_load_publisher_ = nh_mav.advertise<std_msgs::Float32>( "status/cpu_load", 1); cpu_load_avg_publisher_ = nh_mav.advertise<std_msgs::Float32>( "status/cpu_load_avg", 1); if (publish_debug_) { debug_cmd_roll_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/cmd/roll", 1); debug_cmd_pitch_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/cmd/pitch", 1); debug_cmd_yaw_rate_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/cmd/yaw_rate", 1); debug_cmd_thrust_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/cmd/thrust", 1); debug_cmd_yaw_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/cmd/yaw", 1); debug_pid_x_i_term_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/pid/x_i_term", 1); debug_pid_y_i_term_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/pid/y_i_term", 1); debug_pid_yaw_i_term_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/pid/yaw_i_term", 1); debug_pid_z_i_term_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/pid/z_i_term", 1); debug_roll_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/roll", 1); debug_pitch_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/pitch", 1); debug_yaw_publisher_ = nh_mav.advertise<std_msgs::Float32>( "debug/yaw", 1); debug_err_x_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/err_x_bf", 1); debug_err_y_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/err_y_bf", 1); debug_err_vx_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/err_vx_bf", 1); debug_err_vy_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/err_vy_bf", 1); debug_ax_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/acc_x_bf", 1); debug_ay_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/acc_y_bf", 1); debug_az_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/dvz", 1); debug_vx_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/vx_bf", 1); debug_vy_bf_publisher_= nh_mav.advertise<std_msgs::Float32>( "debug/pid/vy_bf", 1); debug_imu_wf_publisher_ = nh_mav.advertise<sensor_msgs::Imu>( "debug/imu_wf", 1); } // **** register callbacks for packets from serial port comm_.registerCallback(MAV_IMU_PKT_ID, &FlyerInterface::processImuData, this); comm_.registerCallback(MAV_POSE_PKT_ID, &FlyerInterface::processPoseData, this); comm_.registerCallback(MAV_RCDATA_PKT_ID, &FlyerInterface::processRCData, this); comm_.registerCallback(MAV_FLIGHT_STATE_PKT_ID, &FlyerInterface::processFlightStateData, this); comm_.registerCallback(MAV_TIMESYNC_PKT_ID, &FlyerInterface::processTimeSyncData, this); comm_.registerCallback(MAV_STATUS_PKT_ID, &FlyerInterface::processStatusData, this); if (publish_debug_) comm_.registerCallback(MAV_CTRL_DEBUG_PKT_ID, &FlyerInterface::processCtrlDebugData, this); // **** register subscribers // Synchronize inputs. Topic subscriptions happen on demand in the connection callback. int queue_size = 5; laser_pose_subscriber_.reset(new PoseStampedSubscriber( nh_mav, "laser_pose_f", queue_size)); laser_vel_subscriber_.reset(new TwistStampedSubscriber( nh_mav, "laser_vel_f", queue_size)); sync_.reset(new Synchronizer( SyncPolicy(queue_size), *laser_pose_subscriber_, *laser_vel_subscriber_)); sync_->registerCallback(boost::bind(&FlyerInterface::laserCallback, this, _1, _2)); height_subscriber_ = nh_mav.subscribe( "laser_height_f", 10, &FlyerInterface::heightCallback, this); cmd_roll_subscriber_ = nh_mav.subscribe( "cmd/roll", 10, &FlyerInterface::cmdRollCallback, this); cmd_pitch_subscriber_ = nh_mav.subscribe( "cmd/pitch", 10, &FlyerInterface::cmdPitchCallback, this); cmd_yaw_rate_subscriber_ = nh_mav.subscribe( "cmd/yaw_rate", 10, &FlyerInterface::cmdYawRateCallback, this); cmd_thrust_subscriber_ = nh_mav.subscribe( "cmd/thrust", 10, &FlyerInterface::cmdThrustCallback, this); cmd_pose_subscriber_ = nh_mav.subscribe( "cmd/pose", 10, &FlyerInterface::cmdPoseCallback, this); cmd_vel_subscriber_ = nh_mav.subscribe( "cmd/vel", 10, &FlyerInterface::cmdVelCallback, this); // **** timers cmd_timer_ = nh_private_.createTimer( ros::Duration(0.05), &FlyerInterface::cmdTimerCallback, this); // **** services advance_state_srv_ = nh_mav.advertiseService( "advanceState", &FlyerInterface::advanceState, this); retreat_state_srv_ = nh_mav.advertiseService( "retreatState", &FlyerInterface::retreatState, this); estop_srv_ = nh_mav.advertiseService( "estop", &FlyerInterface::estop, this); toggle_engage_srv_ = nh_mav.advertiseService( "toggleEngage", &FlyerInterface::toggleEngage, this); takeoff_srv_ = nh_mav.advertiseService( "takeoff", &FlyerInterface::takeoff, this); land_srv_ = nh_mav.advertiseService( "land", &FlyerInterface::land, this); get_flight_state_srv_ = nh_mav.advertiseService( "getFlightState", &FlyerInterface::getFlightState, this); set_ctrl_type_srv_ = nh_mav.advertiseService( "setCtrlType", &FlyerInterface::setCtrlType, this); }
ImuFilter::ImuFilter(ros::NodeHandle nh, ros::NodeHandle nh_private) : nh_(nh), nh_private_(nh_private), initialized_(false), q0(1.0), q1(0.0), q2(0.0), q3(0.0) { ROS_INFO("Starting ImuFilter"); // **** get paramters if (!nh_private_.getParam("gain", gain_)) gain_ = 0.1; if (!nh_private_.getParam("zeta", zeta_)) zeta_ = 0; if (!nh_private_.getParam("use_mag", use_mag_)) use_mag_ = true; if (!nh_private_.getParam("publish_tf", publish_tf_)) publish_tf_ = true; if (!nh_private_.getParam("fixed_frame", fixed_frame_)) fixed_frame_ = "odom"; if (!nh_private_.getParam("constant_dt", constant_dt_)) constant_dt_ = 0.0; // check for illegal constant_dt values if (constant_dt_ < 0.0) { ROS_FATAL("constant_dt parameter is %f, must be >= 0.0. Setting to 0.0", constant_dt_); constant_dt_ = 0.0; } // if constant_dt_ is 0.0 (default), use IMU timestamp to determine dt // otherwise, it will be constant if (constant_dt_ == 0.0) ROS_INFO("Using dt computed from message headers"); else ROS_INFO("Using constant dt of %f sec", constant_dt_); // **** register dynamic reconfigure FilterConfigServer::CallbackType f = boost::bind(&ImuFilter::reconfigCallback, this, _1, _2); config_server_.setCallback(f); // **** register publishers imu_publisher_ = nh_.advertise<sensor_msgs::Imu>( "imu/data", 5); // **** register subscribers // Synchronize inputs. Topic subscriptions happen on demand in the connection callback. int queue_size = 5; imu_subscriber_.reset(new ImuSubscriber( nh_, "imu/data_raw", queue_size)); if (use_mag_) { mag_subscriber_.reset(new MagSubscriber( nh_, "imu/mag", queue_size)); sync_.reset(new Synchronizer( SyncPolicy(queue_size), *imu_subscriber_, *mag_subscriber_)); sync_->registerCallback(boost::bind(&ImuFilter::imuMagCallback, this, _1, _2)); } else { imu_subscriber_->registerCallback(&ImuFilter::imuCallback, this); } }