Ejemplo n.º 1
0
	void handle_flow(const mavlink_message_t *msg) {
		if (flow_pub.getNumSubscribers() == 0)
			return;

		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		mavros_extras::OpticalFlowPtr flow_msg =
			boost::make_shared<mavros_extras::OpticalFlow>();

		// Note: for ENU->NED conversion i swap x & y.
		flow_msg->header.stamp = ros::Time::now();
		flow_msg->flow_x = flow.flow_y;
		flow_msg->flow_y = flow.flow_x;
		flow_msg->flow_comp_m_x	 = flow.flow_comp_m_y;
		flow_msg->flow_comp_m_y	 = flow.flow_comp_m_x;
		flow_msg->quality = flow.quality;
		flow_msg->ground_distance = flow.ground_distance;

		flow_pub.publish(flow_msg);

		/* Optional TODO: send ground_distance in sensor_msgs/Range
		 *                with data filled by spec on used sonar.
		 */
	}
Ejemplo n.º 2
0
void
MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
{
	/* optical flow */
	mavlink_optical_flow_t flow;
	mavlink_msg_optical_flow_decode(msg, &flow);

	struct optical_flow_s f;
	memset(&f, 0, sizeof(f));

	f.timestamp = hrt_absolute_time();
	f.flow_raw_x = flow.flow_x;
	f.flow_raw_y = flow.flow_y;
	f.flow_comp_x_m = flow.flow_comp_m_x;
	f.flow_comp_y_m = flow.flow_comp_m_y;
	f.ground_distance_m = flow.ground_distance;
	f.quality = flow.quality;
	f.sensor_id = flow.sensor_id;

	if (_flow_pub < 0) {
		_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

	} else {
		orb_publish(ORB_ID(optical_flow), _flow_pub, &f);
	}
}
void ml_logger_default_write_optical_flow(ml_logger_t* mll, mavlink_message_t* msg)
{
    /**
         uint64_t time_usec; ///< Timestamp (UNIX)
         float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated
         float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated
         float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
         int16_t flow_x; ///< Flow in pixels in x-sensor direction
         int16_t flow_y; ///< Flow in pixels in y-sensor direction
         uint8_t sensor_id; ///< Sensor ID
         uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
    **/

    if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW)
    {
        mavlink_optical_flow_t of;
        mavlink_msg_optical_flow_decode(msg, &of);

        fprintf(mll->files.optical_flow.fs, "%12" PRIu64 " %12" PRIu64 " %9.6f %9.6f %9.6f %5d %5d %3d %3d\n",
                utils_us_since_epoch(),
                of.time_usec,
                of.flow_comp_m_x,
                of.flow_comp_m_y,
                of.ground_distance,
                of.flow_x,
                of.flow_y,
                of.sensor_id,
                of.quality
                );
        fflush(mll->files.optical_flow.fs);
    }
}
Ejemplo n.º 4
0
static void
handle_message(mavlink_message_t *msg)
{
	if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

		mavlink_command_long_t cmd_mavlink;
		mavlink_msg_command_long_decode(msg, &cmd_mavlink);

		if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
				|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
			//check for MAVLINK terminate command
			if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
				/* This is the link shutdown command, terminate mavlink */
				warnx("terminating...");
				fflush(stdout);
				usleep(50000);

				/* terminate other threads and this thread */
				thread_should_exit = true;

			} else {

				/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
				vcmd.param1 = cmd_mavlink.param1;
				vcmd.param2 = cmd_mavlink.param2;
				vcmd.param3 = cmd_mavlink.param3;
				vcmd.param4 = cmd_mavlink.param4;
				vcmd.param5 = cmd_mavlink.param5;
				vcmd.param6 = cmd_mavlink.param6;
				vcmd.param7 = cmd_mavlink.param7;
				vcmd.command = cmd_mavlink.command;
				vcmd.target_system = cmd_mavlink.target_system;
				vcmd.target_component = cmd_mavlink.target_component;
				vcmd.source_system = msg->sysid;
				vcmd.source_component = msg->compid;
				vcmd.confirmation =  cmd_mavlink.confirmation;

				/* check if topic is advertised */
				if (cmd_pub <= 0) {
					cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
				}

				/* publish */
				orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
			}
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		struct optical_flow_s f;

		f.timestamp = hrt_absolute_time();
		f.flow_raw_x = flow.flow_x;
		f.flow_raw_y = flow.flow_y;
		f.flow_comp_x_m = flow.flow_comp_m_x;
		f.flow_comp_y_m = flow.flow_comp_m_y;
		f.ground_distance_m = flow.ground_distance;
		f.quality = flow.quality;
		f.sensor_id = flow.sensor_id;

		/* check if topic is advertised */
		if (flow_pub <= 0) {
			flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

		} else {
			/* publish */
			orb_publish(ORB_ID(optical_flow), flow_pub, &f);
		}

	}

	if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
		/* Set mode on request */
		mavlink_set_mode_t new_mode;
		mavlink_msg_set_mode_decode(msg, &new_mode);

		/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
		vcmd.param1 = new_mode.base_mode;
		vcmd.param2 = new_mode.custom_mode;
		vcmd.param3 = 0;
		vcmd.param4 = 0;
		vcmd.param5 = 0;
		vcmd.param6 = 0;
		vcmd.param7 = 0;
		vcmd.command = MAV_CMD_DO_SET_MODE;
		vcmd.target_system = new_mode.target_system;
		vcmd.target_component = MAV_COMP_ID_ALL;
		vcmd.source_system = msg->sysid;
		vcmd.source_component = msg->compid;
		vcmd.confirmation = 1;

		/* check if topic is advertised */
		if (cmd_pub <= 0) {
			cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

		} else {
			/* create command */
			orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
		}
	}

	/* Handle Vicon position estimates */
	if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		vicon_position.x = pos.x;
		vicon_position.y = pos.y;
		vicon_position.z = pos.z;

		if (vicon_position_pub <= 0) {
			vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);

		} else {
			orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
		}
	}

	//Mavlink Message from the onboard computer / laserscanner:
	if (msg->msgid == MAVLINK_MSG_ID_DANGER) {
			mavlink_danger_t dang;
			mavlink_msg_danger_decode(msg, &dang);

			struct danger_s d;

			d.time_usec = hrt_absolute_time();
			d.sensor_id = dang.sensor_id;
			d.danger_level = dang.danger_level;
			d.danger_dist = dang.danger_dist;
			d.danger_dir = dang.danger_dir;
			d.avoid_level = dang.avoid_level;
			d.avoid_dir = dang.avoid_dir;
			//check if topic is advertised
			if (danger_pub <= 0) {
				danger_pub = orb_advertise(ORB_ID(danger), &d);
			} else {
				// publish
				orb_publish(ORB_ID(danger), danger_pub, &d);
			}
		}

	/* Handle quadrotor motor setpoints */

	if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
		mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
		mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);

		if (mavlink_system.sysid < 4) {

			/* switch to a receiving link mode */
			gcs_link = false;

			/*
			 * rate control mode - defined by MAVLink
			 */

			uint8_t ml_mode = 0;
			bool ml_armed = false;

			switch (quad_motors_setpoint.mode) {
			case 0:
				ml_armed = false;
				break;

			case 1:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
				ml_armed = true;

				break;

			case 2:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
				ml_armed = true;

				break;

			case 3:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
				break;

			case 4:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
				break;
			}

			offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1]   / (float)INT16_MAX;
			offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1]  / (float)INT16_MAX;
			offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1]    / (float)INT16_MAX;
			offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;

			if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
				ml_armed = false;
			}

			offboard_control_sp.armed = ml_armed;
			offboard_control_sp.mode = ml_mode;

			offboard_control_sp.timestamp = hrt_absolute_time();

			/* check if topic has to be advertised */
			if (offboard_control_sp_pub <= 0) {
				offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);

			} else {
				/* Publish */
				orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
			}
		}
	}

}
Ejemplo n.º 5
0
static void
handle_message(mavlink_message_t *msg)
{
	if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

		mavlink_command_long_t cmd_mavlink;
		mavlink_msg_command_long_decode(msg, &cmd_mavlink);

		if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
				|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
			//check for MAVLINK terminate command
			if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
				/* This is the link shutdown command, terminate mavlink */
				printf("[mavlink] Terminating .. \n");
				fflush(stdout);
				usleep(50000);

				/* terminate other threads and this thread */
				thread_should_exit = true;

			} else {

				/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
				vcmd.param1 = cmd_mavlink.param1;
				vcmd.param2 = cmd_mavlink.param2;
				vcmd.param3 = cmd_mavlink.param3;
				vcmd.param4 = cmd_mavlink.param4;
				vcmd.param5 = cmd_mavlink.param5;
				vcmd.param6 = cmd_mavlink.param6;
				vcmd.param7 = cmd_mavlink.param7;
				// XXX do proper translation
				vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
				vcmd.target_system = cmd_mavlink.target_system;
				vcmd.target_component = cmd_mavlink.target_component;
				vcmd.source_system = msg->sysid;
				vcmd.source_component = msg->compid;
				vcmd.confirmation =  cmd_mavlink.confirmation;

				/* check if topic is advertised */
				if (cmd_pub <= 0) {
					cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

				} else {
					/* publish */
					orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
				}
			}
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		struct optical_flow_s f;

		f.timestamp = flow.time_usec;
		f.flow_raw_x = flow.flow_x;
		f.flow_raw_y = flow.flow_y;
		f.flow_comp_x_m = flow.flow_comp_m_x;
		f.flow_comp_y_m = flow.flow_comp_m_y;
		f.ground_distance_m = flow.ground_distance;
		f.quality = flow.quality;
		f.sensor_id = flow.sensor_id;

		/* check if topic is advertised */
		if (flow_pub <= 0) {
			flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

		} else {
			/* publish */
			orb_publish(ORB_ID(optical_flow), flow_pub, &f);
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
		/* Set mode on request */
		mavlink_set_mode_t new_mode;
		mavlink_msg_set_mode_decode(msg, &new_mode);

		union px4_custom_mode custom_mode;
		custom_mode.data = new_mode.custom_mode;
		/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
		vcmd.param1 = new_mode.base_mode;
		vcmd.param2 = custom_mode.main_mode;
		vcmd.param3 = 0;
		vcmd.param4 = 0;
		vcmd.param5 = 0;
		vcmd.param6 = 0;
		vcmd.param7 = 0;
		vcmd.command = VEHICLE_CMD_DO_SET_MODE;
		vcmd.target_system = new_mode.target_system;
		vcmd.target_component = MAV_COMP_ID_ALL;
		vcmd.source_system = msg->sysid;
		vcmd.source_component = msg->compid;
		vcmd.confirmation = 1;

		/* check if topic is advertised */
		if (cmd_pub <= 0) {
			cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

		} else {
			/* create command */
			orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
		}
	}

	/* Handle Vicon position estimates */
	if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		vicon_position.timestamp = hrt_absolute_time();

		vicon_position.x = pos.x;
		vicon_position.y = pos.y;
		vicon_position.z = pos.z;

		vicon_position.roll = pos.roll;
		vicon_position.pitch = pos.pitch;
		vicon_position.yaw = pos.yaw;

		if (vicon_position_pub <= 0) {
			vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);

		} else {
			orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
		}
	}

	/* Handle quadrotor motor setpoints */

	if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
		mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
		mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);

		if (mavlink_system.sysid < 4) {

			/* switch to a receiving link mode */
			gcs_link = false;

			/*
			 * rate control mode - defined by MAVLink
			 */

			uint8_t ml_mode = 0;
			bool ml_armed = false;

			switch (quad_motors_setpoint.mode) {
			case 0:
				ml_armed = false;
				break;

			case 1:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
				ml_armed = true;

				break;

			case 2:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
				ml_armed = true;

				break;

			case 3:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
				break;

			case 4:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
				break;
			}

			offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1]   / (float)INT16_MAX;
			offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1]  / (float)INT16_MAX;
			offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1]    / (float)INT16_MAX;
			offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;

			if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
				ml_armed = false;
			}

			offboard_control_sp.armed = ml_armed;
			offboard_control_sp.mode = static_cast<enum OFFBOARD_CONTROL_MODE>(ml_mode);

			offboard_control_sp.timestamp = hrt_absolute_time();

			/* check if topic has to be advertised */
			if (offboard_control_sp_pub <= 0) {
				offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);

			} else {
				/* Publish */
				orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
			}
		}
	}

	/* handle status updates of the radio */
	if (msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) {

		struct telemetry_status_s tstatus;

		mavlink_radio_status_t rstatus;
		mavlink_msg_radio_status_decode(msg, &rstatus);

		/* publish telemetry status topic */
		tstatus.timestamp = hrt_absolute_time();
		tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
		tstatus.rssi = rstatus.rssi;
		tstatus.remote_rssi = rstatus.remrssi;
		tstatus.txbuf = rstatus.txbuf;
		tstatus.noise = rstatus.noise;
		tstatus.remote_noise = rstatus.remnoise;
		tstatus.rxerrors = rstatus.rxerrors;
		tstatus.fixed = rstatus.fixed;

		if (telemetry_status_pub == 0) {
			telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus);

		} else {
			orb_publish(ORB_ID(telemetry_status), telemetry_status_pub, &tstatus);
		}
	}

	/*
	 * Only decode hil messages in HIL mode.
	 *
	 * The HIL mode is enabled by the HIL bit flag
	 * in the system mode. Either send a set mode
	 * COMMAND_LONG message or a SET_MODE message
	 */

	if (mavlink_hil_enabled) {

		uint64_t timestamp = hrt_absolute_time();

		if (msg->msgid == MAVLINK_MSG_ID_HIL_SENSOR) {

			mavlink_hil_sensor_t imu;
			mavlink_msg_hil_sensor_decode(msg, &imu);

			/* sensors general */
			hil_sensors.timestamp = hrt_absolute_time();

			/* hil gyro */
			static const float mrad2rad = 1.0e-3f;
			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad;
			hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad;
			hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad;
			hil_sensors.gyro_rad_s[0] = imu.xgyro;
			hil_sensors.gyro_rad_s[1] = imu.ygyro;
			hil_sensors.gyro_rad_s[2] = imu.zgyro;

			/* accelerometer */
			hil_sensors.accelerometer_counter = hil_counter;
			static const float mg2ms2 = 9.8f / 1000.0f;
			hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
			hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
			hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2;
			hil_sensors.accelerometer_m_s2[0] = imu.xacc;
			hil_sensors.accelerometer_m_s2[1] = imu.yacc;
			hil_sensors.accelerometer_m_s2[2] = imu.zacc;
			hil_sensors.accelerometer_mode = 0; // TODO what is this?
			hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16

			/* adc */
			hil_sensors.adc_voltage_v[0] = 0.0f;
			hil_sensors.adc_voltage_v[1] = 0.0f;
			hil_sensors.adc_voltage_v[2] = 0.0f;

			/* magnetometer */
			float mga2ga = 1.0e-3f;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga;
			hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga;
			hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga;
			hil_sensors.magnetometer_ga[0] = imu.xmag;
			hil_sensors.magnetometer_ga[1] = imu.ymag;
			hil_sensors.magnetometer_ga[2] = imu.zmag;
			hil_sensors.magnetometer_range_ga = 32.7f; // int16
			hil_sensors.magnetometer_mode = 0; // TODO what is this
			hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;

			/* baro */
			hil_sensors.baro_pres_mbar = imu.abs_pressure;
			hil_sensors.baro_alt_meter = imu.pressure_alt;
			hil_sensors.baro_temp_celcius = imu.temperature;

			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.accelerometer_counter = hil_counter;

			/* differential pressure */
			hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
			hil_sensors.differential_pressure_counter = hil_counter;

			/* airspeed from differential pressure, ambient pressure and temp */
			struct airspeed_s airspeed;

			float ias = calc_indicated_airspeed(hil_sensors.differential_pressure_pa);
			// XXX need to fix this
			float tas = ias;

			airspeed.timestamp = hrt_absolute_time();
			airspeed.indicated_airspeed_m_s = ias;
			airspeed.true_airspeed_m_s = tas;

			if (pub_hil_airspeed < 0) {
				pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);

			} else {
				orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
			}

			//warnx("SENSOR: IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);

			/* individual sensor publications */
			struct gyro_report gyro;
			gyro.x_raw = imu.xgyro / mrad2rad;
			gyro.y_raw = imu.ygyro / mrad2rad;
			gyro.z_raw = imu.zgyro / mrad2rad;
			gyro.x = imu.xgyro;
			gyro.y = imu.ygyro;
			gyro.z = imu.zgyro;
			gyro.temperature = imu.temperature;
			gyro.timestamp = hrt_absolute_time();

			if (pub_hil_gyro < 0) {
				pub_hil_gyro = orb_advertise(ORB_ID(sensor_gyro), &gyro);

			} else {
				orb_publish(ORB_ID(sensor_gyro), pub_hil_gyro, &gyro);
			}

			struct accel_report accel;

			accel.x_raw = imu.xacc / mg2ms2;

			accel.y_raw = imu.yacc / mg2ms2;

			accel.z_raw = imu.zacc / mg2ms2;

			accel.x = imu.xacc;

			accel.y = imu.yacc;

			accel.z = imu.zacc;

			accel.temperature = imu.temperature;

			accel.timestamp = hrt_absolute_time();

			if (pub_hil_accel < 0) {
				pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);

			} else {
				orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
			}

			struct mag_report mag;

			mag.x_raw = imu.xmag / mga2ga;

			mag.y_raw = imu.ymag / mga2ga;

			mag.z_raw = imu.zmag / mga2ga;

			mag.x = imu.xmag;

			mag.y = imu.ymag;

			mag.z = imu.zmag;

			mag.timestamp = hrt_absolute_time();

			if (pub_hil_mag < 0) {
				pub_hil_mag = orb_advertise(ORB_ID(sensor_mag), &mag);

			} else {
				orb_publish(ORB_ID(sensor_mag), pub_hil_mag, &mag);
			}

			struct baro_report baro;

			baro.pressure = imu.abs_pressure;

			baro.altitude = imu.pressure_alt;

			baro.temperature = imu.temperature;

			baro.timestamp = hrt_absolute_time();

			if (pub_hil_baro < 0) {
				pub_hil_baro = orb_advertise(ORB_ID(sensor_baro), &baro);

			} else {
				orb_publish(ORB_ID(sensor_baro), pub_hil_baro, &baro);
			}

			/* publish combined sensor topic */
			if (pub_hil_sensors > 0) {
				orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			} else {
				pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
			}

			/* fill in HIL battery status */
			hil_battery_status.timestamp = hrt_absolute_time();
			hil_battery_status.voltage_v = 11.1f;
			hil_battery_status.current_a = 10.0f;

			/* lazily publish the battery voltage */
			if (pub_hil_battery > 0) {
				orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);

			} else {
				pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
			}

			// increment counters
			hil_counter++;
			hil_frames++;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil sensor at %d hz\n", hil_frames / 10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_HIL_GPS) {

			mavlink_hil_gps_t gps;
			mavlink_msg_hil_gps_decode(msg, &gps);

			/* gps */
			hil_gps.timestamp_position = gps.time_usec;
			hil_gps.time_gps_usec = gps.time_usec;
			hil_gps.lat = gps.lat;
			hil_gps.lon = gps.lon;
			hil_gps.alt = gps.alt;
			hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
			hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
			hil_gps.s_variance_m_s = 5.0f;
			hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
			hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s

			/* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */
			float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f;

			/* go back to -PI..PI */
			if (heading_rad > M_PI_F)
				heading_rad -= 2.0f * M_PI_F;

			hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m
			hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m
			hil_gps.vel_d_m_s = gps.vd * 1e-2f; // from cm to m
			hil_gps.vel_ned_valid = true;
			/* COG (course over ground) is spec'ed as -PI..+PI */
			hil_gps.cog_rad = heading_rad;
			hil_gps.fix_type = gps.fix_type;
			hil_gps.satellites_visible = gps.satellites_visible;

			/* publish GPS measurement data */
			if (pub_hil_gps > 0) {
				orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);

			} else {
				pub_hil_gps = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
			}

		}

		if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE_QUATERNION) {

			mavlink_hil_state_quaternion_t hil_state;
			mavlink_msg_hil_state_quaternion_decode(msg, &hil_state);

			struct airspeed_s airspeed;
			airspeed.timestamp = hrt_absolute_time();
			airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f;
			airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f;

			if (pub_hil_airspeed < 0) {
				pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);

			} else {
				orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
			}

			uint64_t timestamp = hrt_absolute_time();

			// publish global position	
			if (pub_hil_global_pos > 0) {
				orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
				// global position packet
				hil_global_pos.timestamp = timestamp;
				hil_global_pos.valid = true;
				hil_global_pos.lat = hil_state.lat;
				hil_global_pos.lon = hil_state.lon;
				hil_global_pos.alt = hil_state.alt / 1000.0f;
				hil_global_pos.vx = hil_state.vx / 100.0f;
				hil_global_pos.vy = hil_state.vy / 100.0f;
				hil_global_pos.vz = hil_state.vz / 100.0f;

			} else {
				pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
			}

			// publish local position
			if (pub_hil_local_pos > 0) {
				float x;
				float y;
				bool landed = hil_state.alt/1000.0f < (alt0 + 0.1); // XXX improve?
				double lat = hil_state.lat*1e-7;
				double lon = hil_state.lon*1e-7;
				map_projection_project(lat, lon, &x, &y); 
				hil_local_pos.timestamp = timestamp;
				hil_local_pos.xy_valid = true;
				hil_local_pos.z_valid = true;
				hil_local_pos.v_xy_valid = true;
				hil_local_pos.v_z_valid = true;
				hil_local_pos.x = x;
				hil_local_pos.y = y;
				hil_local_pos.z = alt0 - hil_state.alt/1000.0f;
				hil_local_pos.vx = hil_state.vx/100.0f;
				hil_local_pos.vy = hil_state.vy/100.0f;
				hil_local_pos.vz = hil_state.vz/100.0f;
				hil_local_pos.yaw = hil_attitude.yaw;
				hil_local_pos.xy_global = true;
				hil_local_pos.z_global = true;
				hil_local_pos.ref_timestamp = timestamp;
				hil_local_pos.ref_lat = hil_state.lat;
				hil_local_pos.ref_lon = hil_state.lon;
				hil_local_pos.ref_alt = alt0;
				hil_local_pos.landed = landed;
				orb_publish(ORB_ID(vehicle_local_position), pub_hil_local_pos, &hil_local_pos);
			} else {
				pub_hil_local_pos = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos);
				lat0 = hil_state.lat;
				lon0 = hil_state.lon;
				alt0 = hil_state.alt / 1000.0f;
				map_projection_init(hil_state.lat, hil_state.lon);
			}

			/* Calculate Rotation Matrix */
			math::Quaternion q(hil_state.attitude_quaternion);
			math::Dcm C_nb(q);
			math::EulerAngles euler(C_nb);

			/* set rotation matrix */
			for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
					hil_attitude.R[i][j] = C_nb(i, j);

			hil_attitude.R_valid = true;

			/* set quaternion */
			hil_attitude.q[0] = q(0);
			hil_attitude.q[1] = q(1);
			hil_attitude.q[2] = q(2);
			hil_attitude.q[3] = q(3);
			hil_attitude.q_valid = true;

			hil_attitude.roll = euler.getPhi();
			hil_attitude.pitch = euler.getTheta();
			hil_attitude.yaw = euler.getPsi();
			hil_attitude.rollspeed = hil_state.rollspeed;
			hil_attitude.pitchspeed = hil_state.pitchspeed;
			hil_attitude.yawspeed = hil_state.yawspeed;

			/* set timestamp and notify processes (broadcast) */
			hil_attitude.timestamp = hrt_absolute_time();

			if (pub_hil_attitude > 0) {
				orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);

			} else {
				pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
			}

			struct accel_report accel;

			accel.x_raw = hil_state.xacc / 9.81f * 1e3f;

			accel.y_raw = hil_state.yacc / 9.81f * 1e3f;

			accel.z_raw = hil_state.zacc / 9.81f * 1e3f;

			accel.x = hil_state.xacc;

			accel.y = hil_state.yacc;

			accel.z = hil_state.zacc;

			accel.temperature = 25.0f;

			accel.timestamp = hrt_absolute_time();

			if (pub_hil_accel < 0) {
				pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);

			} else {
				orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
			}

			/* fill in HIL battery status */
			hil_battery_status.timestamp = hrt_absolute_time();
			hil_battery_status.voltage_v = 11.1f;
			hil_battery_status.current_a = 10.0f;

			/* lazily publish the battery voltage */
			if (pub_hil_battery > 0) {
				orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);

			} else {
				pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
			mavlink_manual_control_t man;
			mavlink_msg_manual_control_decode(msg, &man);

			struct rc_channels_s rc_hil;
			memset(&rc_hil, 0, sizeof(rc_hil));
			static orb_advert_t rc_pub = 0;

			rc_hil.timestamp = hrt_absolute_time();
			rc_hil.chan_count = 4;

			rc_hil.chan[0].scaled = man.x / 1000.0f;
			rc_hil.chan[1].scaled = man.y / 1000.0f;
			rc_hil.chan[2].scaled = man.r / 1000.0f;
			rc_hil.chan[3].scaled = man.z / 1000.0f;

			struct manual_control_setpoint_s mc;
			static orb_advert_t mc_pub = 0;

			int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));

			/* get a copy first, to prevent altering values that are not sent by the mavlink command */
			orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &mc);

			mc.timestamp = rc_hil.timestamp;
			mc.roll = man.x / 1000.0f;
			mc.pitch = man.y / 1000.0f;
			mc.yaw = man.r / 1000.0f;
			mc.throttle = man.z / 1000.0f;

			/* fake RC channels with manual control input from simulator */


			if (rc_pub == 0) {
				rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil);

			} else {
				orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil);
			}

			if (mc_pub == 0) {
				mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc);

			} else {
				orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc);
			}
		}
	}
}
Ejemplo n.º 6
0
static void
handle_message(mavlink_message_t *msg)
{
	if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

		mavlink_command_long_t cmd_mavlink;
		mavlink_msg_command_long_decode(msg, &cmd_mavlink);

		if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
				|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
			//check for MAVLINK terminate command
			if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
				/* This is the link shutdown command, terminate mavlink */
				printf("[mavlink] Terminating .. \n");
				fflush(stdout);
				usleep(50000);

				/* terminate other threads and this thread */
				thread_should_exit = true;

			} else {

				/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
				vcmd.param1 = cmd_mavlink.param1;
				vcmd.param2 = cmd_mavlink.param2;
				vcmd.param3 = cmd_mavlink.param3;
				vcmd.param4 = cmd_mavlink.param4;
				vcmd.param5 = cmd_mavlink.param5;
				vcmd.param6 = cmd_mavlink.param6;
				vcmd.param7 = cmd_mavlink.param7;
				vcmd.command = cmd_mavlink.command;
				vcmd.target_system = cmd_mavlink.target_system;
				vcmd.target_component = cmd_mavlink.target_component;
				vcmd.source_system = msg->sysid;
				vcmd.source_component = msg->compid;
				vcmd.confirmation =  cmd_mavlink.confirmation;

				/* check if topic is advertised */
				if (cmd_pub <= 0) {
					cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
				}

				/* publish */
				orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
			}
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		struct optical_flow_s f;

		f.timestamp = flow.time_usec;
		f.flow_raw_x = flow.flow_x;
		f.flow_raw_y = flow.flow_y;
		f.flow_comp_x_m = flow.flow_comp_m_x;
		f.flow_comp_y_m = flow.flow_comp_m_y;
		f.ground_distance_m = flow.ground_distance;
		f.quality = flow.quality;
		f.sensor_id = flow.sensor_id;

		/* check if topic is advertised */
		if (flow_pub <= 0) {
			flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

		} else {
			/* publish */
			orb_publish(ORB_ID(optical_flow), flow_pub, &f);
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
		/* Set mode on request */
		mavlink_set_mode_t new_mode;
		mavlink_msg_set_mode_decode(msg, &new_mode);

		/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
		vcmd.param1 = new_mode.base_mode;
		vcmd.param2 = new_mode.custom_mode;
		vcmd.param3 = 0;
		vcmd.param4 = 0;
		vcmd.param5 = 0;
		vcmd.param6 = 0;
		vcmd.param7 = 0;
		vcmd.command = MAV_CMD_DO_SET_MODE;
		vcmd.target_system = new_mode.target_system;
		vcmd.target_component = MAV_COMP_ID_ALL;
		vcmd.source_system = msg->sysid;
		vcmd.source_component = msg->compid;
		vcmd.confirmation = 1;

		/* check if topic is advertised */
		if (cmd_pub <= 0) {
			cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

		} else {
			/* create command */
			orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
		}
	}

	/* Handle Vicon position estimates */
	if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		vicon_position.timestamp = hrt_absolute_time();

		vicon_position.x = pos.x;
		vicon_position.y = pos.y;
		vicon_position.z = pos.z;

		vicon_position.roll = pos.roll;
		vicon_position.pitch = pos.pitch;
		vicon_position.yaw = pos.yaw;

		if (vicon_position_pub <= 0) {
			vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);

		} else {
			orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
		}
	}

	/* Handle quadrotor motor setpoints */

	if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
		mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
		mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);

		if (mavlink_system.sysid < 4) {

			/* switch to a receiving link mode */
			gcs_link = false;

			/*
			 * rate control mode - defined by MAVLink
			 */

			uint8_t ml_mode = 0;
			bool ml_armed = false;

			switch (quad_motors_setpoint.mode) {
			case 0:
				ml_armed = false;
				break;

			case 1:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
				ml_armed = true;

				break;

			case 2:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
				ml_armed = true;

				break;

			case 3:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
				break;

			case 4:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
				break;
			}

			offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1]   / (float)INT16_MAX;
			offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1]  / (float)INT16_MAX;
			offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1]    / (float)INT16_MAX;
			offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;

			if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
				ml_armed = false;
			}

			offboard_control_sp.armed = ml_armed;
			offboard_control_sp.mode = ml_mode;

			offboard_control_sp.timestamp = hrt_absolute_time();

			/* check if topic has to be advertised */
			if (offboard_control_sp_pub <= 0) {
				offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);

			} else {
				/* Publish */
				orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
			}
		}
	}

	/*
	 * Only decode hil messages in HIL mode.
	 *
	 * The HIL mode is enabled by the HIL bit flag
	 * in the system mode. Either send a set mode
	 * COMMAND_LONG message or a SET_MODE message
	 */

	if (mavlink_hil_enabled) {

		uint64_t timestamp = hrt_absolute_time();

		/* TODO, set ground_press/ temp during calib */
		static const float ground_press = 1013.25f; // mbar
		static const float ground_tempC = 21.0f;
		static const float ground_alt = 0.0f;
		static const float T0 = 273.15;
		static const float R = 287.05f;
		static const float g = 9.806f;

		if (msg->msgid == MAVLINK_MSG_ID_RAW_IMU) {

			mavlink_raw_imu_t imu;
			mavlink_msg_raw_imu_decode(msg, &imu);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* sensors general */
			hil_sensors.timestamp = imu.time_usec;

			/* hil gyro */
			static const float mrad2rad = 1.0e-3f;
			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.gyro_raw[0] = imu.xgyro;
			hil_sensors.gyro_raw[1] = imu.ygyro;
			hil_sensors.gyro_raw[2] = imu.zgyro;
			hil_sensors.gyro_rad_s[0] = imu.xgyro * mrad2rad;
			hil_sensors.gyro_rad_s[1] = imu.ygyro * mrad2rad;
			hil_sensors.gyro_rad_s[2] = imu.zgyro * mrad2rad;

			/* accelerometer */
			hil_sensors.accelerometer_counter = hil_counter;
			static const float mg2ms2 = 9.8f / 1000.0f;
			hil_sensors.accelerometer_raw[0] = imu.xacc;
			hil_sensors.accelerometer_raw[1] = imu.yacc;
			hil_sensors.accelerometer_raw[2] = imu.zacc;
			hil_sensors.accelerometer_m_s2[0] = mg2ms2 * imu.xacc;
			hil_sensors.accelerometer_m_s2[1] = mg2ms2 * imu.yacc;
			hil_sensors.accelerometer_m_s2[2] = mg2ms2 * imu.zacc;
			hil_sensors.accelerometer_mode = 0; // TODO what is this?
			hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16

			/* adc */
			hil_sensors.adc_voltage_v[0] = 0;
			hil_sensors.adc_voltage_v[1] = 0;
			hil_sensors.adc_voltage_v[2] = 0;

			/* magnetometer */
			float mga2ga = 1.0e-3f;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.magnetometer_raw[0] = imu.xmag;
			hil_sensors.magnetometer_raw[1] = imu.ymag;
			hil_sensors.magnetometer_raw[2] = imu.zmag;
			hil_sensors.magnetometer_ga[0] = imu.xmag * mga2ga;
			hil_sensors.magnetometer_ga[1] = imu.ymag * mga2ga;
			hil_sensors.magnetometer_ga[2] = imu.zmag * mga2ga;
			hil_sensors.magnetometer_range_ga = 32.7f; // int16
			hil_sensors.magnetometer_mode = 0; // TODO what is this
			hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;

			/* publish */
			orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil imu at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) {

			mavlink_highres_imu_t imu;
			mavlink_msg_highres_imu_decode(msg, &imu);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* sensors general */
			hil_sensors.timestamp = imu.time_usec;

			/* hil gyro */
			static const float mrad2rad = 1.0e-3f;
			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad;
			hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad;
			hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad;
			hil_sensors.gyro_rad_s[0] = imu.xgyro;
			hil_sensors.gyro_rad_s[1] = imu.ygyro;
			hil_sensors.gyro_rad_s[2] = imu.zgyro;

			/* accelerometer */
			hil_sensors.accelerometer_counter = hil_counter;
			static const float mg2ms2 = 9.8f / 1000.0f;
			hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
			hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
			hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2;
			hil_sensors.accelerometer_m_s2[0] = imu.xacc;
			hil_sensors.accelerometer_m_s2[1] = imu.yacc;
			hil_sensors.accelerometer_m_s2[2] = imu.zacc;
			hil_sensors.accelerometer_mode = 0; // TODO what is this?
			hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16

			/* adc */
			hil_sensors.adc_voltage_v[0] = 0;
			hil_sensors.adc_voltage_v[1] = 0;
			hil_sensors.adc_voltage_v[2] = 0;

			/* magnetometer */
			float mga2ga = 1.0e-3f;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga;
			hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga;
			hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga;
			hil_sensors.magnetometer_ga[0] = imu.xmag;
			hil_sensors.magnetometer_ga[1] = imu.ymag;
			hil_sensors.magnetometer_ga[2] = imu.zmag;
			hil_sensors.magnetometer_range_ga = 32.7f; // int16
			hil_sensors.magnetometer_mode = 0; // TODO what is this
			hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;

			hil_sensors.baro_pres_mbar = imu.abs_pressure;

			float tempC =  imu.temperature;
			float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f;
			float h =  ground_alt + (R / g) * tempAvgK * logf(ground_press / imu.abs_pressure);

			hil_sensors.baro_alt_meter = h;
			hil_sensors.baro_temp_celcius = imu.temperature;

			/* publish */
			orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil imu at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_GPS_RAW_INT) {

			mavlink_gps_raw_int_t gps;
			mavlink_msg_gps_raw_int_decode(msg, &gps);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* gps */
			hil_gps.timestamp_position = gps.time_usec;
//			hil_gps.counter = hil_counter++;
			hil_gps.time_gps_usec = gps.time_usec;
			hil_gps.lat = gps.lat;
			hil_gps.lon = gps.lon;
			hil_gps.alt = gps.alt;
//			hil_gps.counter_pos_valid = hil_counter++;
			hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
			hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
			hil_gps.s_variance_m_s = 100; // XXX 100 m/s variance?
			hil_gps.p_variance_m = 100; // XXX 100 m variance?
			hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
			hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
			hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
			hil_gps.vel_d_m_s = 0.0f;
			hil_gps.cog_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; // from deg*100 to rad
			hil_gps.fix_type = gps.fix_type;
			hil_gps.satellites_visible = gps.satellites_visible;

			/* publish */
			orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil gps at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_RAW_PRESSURE) {

			mavlink_raw_pressure_t press;
			mavlink_msg_raw_pressure_decode(msg, &press);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* sensors general */
			hil_sensors.timestamp = press.time_usec;

			/* baro */

			float tempC =  press.temperature / 100.0f;
			float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f;
			float h =  ground_alt + (R / g) * tempAvgK * logf(ground_press / press.press_abs);
			hil_sensors.baro_counter = hil_counter;
			hil_sensors.baro_pres_mbar = press.press_abs;
			hil_sensors.baro_alt_meter = h;
			hil_sensors.baro_temp_celcius = tempC;

			/* publish */
			orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil pressure at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) {

			mavlink_hil_state_t hil_state;
			mavlink_msg_hil_state_decode(msg, &hil_state);

			/* Calculate Rotation Matrix */
			//TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode

			if (mavlink_system.type == MAV_TYPE_FIXED_WING) {
				//TODO: assuming low pitch and roll values for now
				hil_attitude.R[0][0] = cosf(hil_state.yaw);
				hil_attitude.R[0][1] = sinf(hil_state.yaw);
				hil_attitude.R[0][2] = 0.0f;

				hil_attitude.R[1][0] = -sinf(hil_state.yaw);
				hil_attitude.R[1][1] = cosf(hil_state.yaw);
				hil_attitude.R[1][2] = 0.0f;

				hil_attitude.R[2][0] = 0.0f;
				hil_attitude.R[2][1] = 0.0f;
				hil_attitude.R[2][2] = 1.0f;

				hil_attitude.R_valid = true;
			}

			hil_global_pos.lat = hil_state.lat;
			hil_global_pos.lon = hil_state.lon;
			hil_global_pos.alt = hil_state.alt / 1000.0f;
			hil_global_pos.vx = hil_state.vx / 100.0f;
			hil_global_pos.vy = hil_state.vy / 100.0f;
			hil_global_pos.vz = hil_state.vz / 100.0f;


			/* set timestamp and notify processes (broadcast) */
			hil_global_pos.timestamp = hrt_absolute_time();
			orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);

			hil_attitude.roll = hil_state.roll;
			hil_attitude.pitch = hil_state.pitch;
			hil_attitude.yaw = hil_state.yaw;
			hil_attitude.rollspeed = hil_state.rollspeed;
			hil_attitude.pitchspeed = hil_state.pitchspeed;
			hil_attitude.yawspeed = hil_state.yawspeed;

			/* set timestamp and notify processes (broadcast) */
			hil_attitude.timestamp = hrt_absolute_time();
			orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);
		}

		if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
			mavlink_manual_control_t man;
			mavlink_msg_manual_control_decode(msg, &man);

			struct rc_channels_s rc_hil;
			memset(&rc_hil, 0, sizeof(rc_hil));
			static orb_advert_t rc_pub = 0;

			rc_hil.timestamp = hrt_absolute_time();
			rc_hil.chan_count = 4;

			rc_hil.chan[0].scaled = man.x / 1000.0f;
			rc_hil.chan[1].scaled = man.y / 1000.0f;
			rc_hil.chan[2].scaled = man.r / 1000.0f;
			rc_hil.chan[3].scaled = man.z / 1000.0f;

			struct manual_control_setpoint_s mc;
			static orb_advert_t mc_pub = 0;

			int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));

			/* get a copy first, to prevent altering values that are not sent by the mavlink command */
			orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &mc);

			mc.timestamp = rc_hil.timestamp;
			mc.roll = man.x / 1000.0f;
			mc.pitch = man.y / 1000.0f;
			mc.yaw = man.r / 1000.0f;
			mc.throttle = man.z / 1000.0f;

			/* fake RC channels with manual control input from simulator */


			if (rc_pub == 0) {
				rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil);

			} else {
				orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil);
			}

			if (mc_pub == 0) {
				mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc);

			} else {
				orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc);
			}
		}
	}
}
Ejemplo n.º 7
0
bool Flow_px4::update(void)
{
    Mavlink_stream::msg_received_t* rec = NULL;

    // Receive incoming bytes
    while (mavlink_stream_.receive(rec))
    {
        // Get pointer to new message
        mavlink_message_t* msg = &rec->msg;

        // declare messages
        mavlink_optical_flow_t          optical_flow_msg;
        mavlink_data_transmission_handshake_t   handshake_msg;
        mavlink_encapsulated_data_t     data_msg;

        switch (msg->msgid)
        {
            case MAVLINK_MSG_ID_OPTICAL_FLOW:
                // Decode message
                mavlink_msg_optical_flow_decode(msg, &optical_flow_msg);
                break;

            case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
                // Decode message
                mavlink_msg_data_transmission_handshake_decode(msg, &handshake_msg);

                // Get type of handshake
                switch (handshake_msg.jpg_quality)
                {
                    case 0:
                        handshake_state = FLOW_HANDSHAKE_DATA;
                        break;

                    case 255:
                        handshake_state = FLOW_HANDSHAKE_METADATA;
                        break;

                    default:
                        handshake_state = FLOW_HANDSHAKE_DATA;
                        break;
                }

                // Get number of of vectors
                of_count        = handshake_msg.width;
                if (of_count > 125)
                {
                    of_count = 125;
                }

                // Get total payload size
                packet_count_       = handshake_msg.packets;
                byte_count_       = handshake_msg.size;
                if (byte_count_ > 500)
                {
                    byte_count_ = 500;
                }
                break;

            case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
                // Decode message
                mavlink_msg_encapsulated_data_decode(msg, &data_msg);

                // Handle according to hanshake state
                switch (handshake_state)
                {
                    case FLOW_HANDSHAKE_METADATA:
                        if (data_msg.seqnr < packet_count_ - 1)
                        {
                            // not last packet
                            for (uint32_t i = 0; i < MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN; ++i)
                            {
                                of_loc_tmp_.data[i + data_msg.seqnr * MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN] = data_msg.data[i];
                            }
                        }
                        else if (data_msg.seqnr < packet_count_)
                        {
                            // last packet
                            for (uint32_t i = 0; i < byte_count_; ++i)
                            {
                                of_loc_tmp_.data[i + data_msg.seqnr * MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN] = data_msg.data[i];
                            }

                            // swap bytes
                            for (uint32_t i = 0; i < of_count; ++i)
                            {
                                of_loc.x[i] =  endian_rev16s(of_loc_tmp_.x[i]);
                                of_loc.y[i] = endian_rev16s(of_loc_tmp_.y[i]);
                            }

                        }
                        break;

                    default:
                        if (data_msg.seqnr < (packet_count_ - 1))
                        {
                            // not last packet
                            for (uint32_t i = 0; i < MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN; ++i)
                            {
                                of_tmp_.data[i + data_msg.seqnr * MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN] = data_msg.data[i];
                            }
                        }
                        else if (data_msg.seqnr == (packet_count_ - 1))
                        {
                            // last packet
                            for (uint32_t i = 0; i < byte_count_ % MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN; ++i)
                            {
                                of_tmp_.data[i + data_msg.seqnr * MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN] = data_msg.data[i];
                            }

                            // swap bytes and filter for high frequency noise
                            for (int i = 0; i < of_count; ++i)
                            {
                                of.x[i] = filter_constant * 0.001f * (float)(endian_rev16s(of_tmp_.x[i])) +
                                          (1.0f - filter_constant) * of.x[i];
                                of.y[i] = filter_constant * 0.001f * (float)(endian_rev16s(of_tmp_.y[i])) +
                                          (1.0f - filter_constant) * of.y[i];
                            }

                            // Update time
                            last_update_us  = time_keeper_get_us();
                        }
                        break;
                }
                break;

            default:
                break;
        }
    }

    return true;
}
Ejemplo n.º 8
0
int main(int argc, char** argv)
{
    int portNum = -1;
    char portArgBuf[6];
    char fName[0xff];

    /// Connect VICON
    initialize_VICON();


    srand ( time(NULL) );

    sprintf_s(fName,"data-%d.txt",rand());

    fp = fopen(fName,"w");

    if(fp == NULL)
    {
        printf("Fopen failed!\n");
        return -1;
    }

    /// Timer Thread function.
    HANDLE hThread = ::CreateThread(NULL, NULL, ThreadProc, NULL, NULL, NULL);
    CloseHandle(hThread);

    if(argc < 2)
    {
        printf("Specify port (e.g., COM1)\n");
        return -1;
    }

    sscanf_s(argv[1],"COM%d",&portNum);

    if(portNum < 0)
    {
        printf("Specify valid port %d\n",portNum);
        return -1;
    }
    else
    {
        printf("Port COM%d opening... \n",portNum);
        sprintf_s(portArgBuf,"COM%d",portNum);
    }

    hSerial = CreateFile(portArgBuf,
                         GENERIC_READ | GENERIC_WRITE,
                         0,
                         NULL,
                         OPEN_EXISTING,
                         FILE_ATTRIBUTE_NORMAL,
                         NULL);

    if(hSerial == INVALID_HANDLE_VALUE)
    {
        if(GetLastError() == ERROR_FILE_NOT_FOUND)
        {
            printf("Invalid port.\n");
            return -1;
        }
        else
        {
            printf("ErrorNo %d\n",GetLastError());
            return -1;
        }
    }

    dcbSerialParams.DCBlength = sizeof(dcbSerialParams);

    if(!GetCommState(hSerial,&dcbSerialParams))
    {
        printf("Error getting state\n");
        return -1;
    }

    //dcbSerialParams.BaudRate = CBR_115200;
    dcbSerialParams.BaudRate = CBR_57600;
    dcbSerialParams.ByteSize = 8;
    dcbSerialParams.StopBits = ONESTOPBIT;
    dcbSerialParams.Parity = NOPARITY;

    if(!SetCommState(hSerial,&dcbSerialParams))
    {
        printf("Error setting serial port state\n");
        return -1;
    }

    timeouts.ReadIntervalTimeout = 50000;
    timeouts.ReadTotalTimeoutConstant = 50000;
    timeouts.ReadTotalTimeoutMultiplier = 10000;
    timeouts.WriteTotalTimeoutConstant = 50000;
    timeouts.WriteTotalTimeoutMultiplier = 10000;

    if(!SetCommTimeouts(hSerial,&timeouts))
    {
        printf("Error setting timeout\n");
        return -1;
    }

    uint8_t szBuff = 0;
    DWORD dwBytesRead = 0;
    DWORD dwBytesWritten = 0;

    /// Mavlink
    mavlink_status_t lastStatus;
    lastStatus.packet_rx_drop_count = 0;

    /// System information
    mavlink_system_t mavlink_system;
    mavlink_system.sysid = 255;                   ///< ID 255
    mavlink_system.compid = 0;     ///< The component sending the message is the IMU, it could be also a Linux process

    /// Sending buffer
    mavlink_message_t sendMsg;
    uint8_t sendBuf[MAVLINK_MAX_PACKET_LEN];
    uint16_t len = 0;

    printf("Open success.\n");

    while(!_kbhit())
    {
        mavlink_message_t message;
        mavlink_status_t status;
        uint8_t msgReceived = false;

        if(!ReadFile(hSerial,&szBuff,1,&dwBytesRead,NULL))
        {
            printf("Read error %d\n",GetLastError());
            dwBytesRead = 0;
        }
        else
        {
            msgReceived = mavlink_parse_char(MAVLINK_COMM_0,szBuff,&message,&status);
            //printf("%d ",szBuff);
            //printf("%d bytes read\n",dwBytesRead);

            //if(mavlink_parse_char(0,szBuff,&message,&status))
            //{
            //printf("Received message with ID %d, sequence: %d from component %d of system %d\n", message.msgid, message.seq, message.compid, message.sysid);
            //}

            if (lastStatus.packet_rx_drop_count != status.packet_rx_drop_count)
            {
                printf("ERROR: DROPPED %d PACKETS\n", status.packet_rx_drop_count);
            }

            lastStatus = status;
        }

        if(msgReceived)
        {
            //printf("Received message with ID %d, sequence: %d from component %d of system %d\n", message.msgid, message.seq, message.compid, message.sysid);

            switch(message.msgid)
            {
            case MAVLINK_MSG_ID_HEARTBEAT:
                if(isLiveChecked == false)
                {
                    // Request data stream
                    //mavlink_msg_request_data_stream_pack(mavlink_system.sysid, mavlink_system.compid,&sendMsg,message.sysid,message.compid,MAV_DATA_STREAM_RAW_SENSORS,10,1);
                    mavlink_msg_request_data_stream_pack(mavlink_system.sysid, mavlink_system.compid,&sendMsg,message.sysid,message.compid,MAV_DATA_STREAM_EXTRA3,50,1);

                    len = mavlink_msg_to_send_buffer(sendBuf,&sendMsg);

                    if(!WriteFile(hSerial,sendBuf,len,&dwBytesWritten,NULL))
                    {
                        printf("Send error : %d\n",GetLastError());
                    }
                    else
                    {
                        printf("Ask success %d/%d\n",len,dwBytesWritten);
                        //isLiveChecked = true;
                    }
                }
                break;

            case MAVLINK_MSG_ID_OPTICAL_FLOW:
                isLiveChecked = true;
                mavlink_msg_optical_flow_decode(&message,&optical_flow);
                break;

            case MAVLINK_MSG_ID_STATE_CORRECTION:
                isLiveChecked = true;
                mavlink_msg_state_correction_decode(&message,&state_error);
                break;

            case MAVLINK_MSG_ID_SYS_STATUS:
                printf("[STATUS] mode:%d\n",mavlink_msg_sys_status_get_status(&message));
                break;

            default:
                printf("Unknown message %d\n",message.msgid);
                break;
            }

            msgReceived = false;
        }
    }

    CloseHandle(hSerial);
    fclose(fp);

    printf("File closed\n");

    printf("Terminated");

    return 0;
}