COMM_FRAME* navigation_pack_rc_channels_scaled()
{
	static COMM_FRAME frame;

	uint8_t port             = 0;
	int16_t chan7_scaled = 0;
	int16_t chan8_scaled = 0;
	uint8_t rssi             = 0;

	int16_t left_side = navigation_status.motor_values[0];
	int16_t right_side = navigation_status.motor_values[1];

	//get currents
	static int32_t sensor_values[N_WHEELS];

	/* initialize to 0 to reset the running average inside the adc readout function */
	sensor_values[0] = 0;
	sensor_values[1] = 0;
	sensor_values[2] = 0;
	sensor_values[3] = 0;

	adc_read_motor_sensors(sensor_values);

	uint32_t msec = ms_since_boot();

	mavlink_msg_rc_channels_scaled_pack(mavlink_system.sysid, MAV_COMP_ID_PATHPLANNER, &(frame.mavlink_message),
				   msec, port, sensor_values[0]/100,sensor_values[1]/100, sensor_values[2]/100, sensor_values[3]/100,
				   chan7_scaled, chan8_scaled, left_side, right_side,  rssi);

	return &frame;
}
Пример #2
0
task_return_t remote_send_scaled(const remote_t* remote)
{
    mavlink_message_t msg;
    mavlink_msg_rc_channels_scaled_pack(	remote->mavlink_stream->sysid,
                                            remote->mavlink_stream->compid,
                                            &msg,
                                            time_keeper_get_millis(),
                                            0,
                                            remote->channels[0] * 10000.0f,
                                            remote->channels[1] * 10000.0f,
                                            remote->channels[2] * 10000.0f,
                                            remote->channels[3] * 10000.0f,
                                            remote->channels[4] * 10000.0f,
                                            remote->channels[5] * 10000.0f,
                                            remote->channels[6] * 10000.0f,
                                            remote->channels[7] * 10000.0f,
                                            remote->mode.current_desired_mode.byte );
    // remote->signal_quality	);

    mavlink_stream_send(remote->mavlink_stream, &msg);

    return TASK_RUN_SUCCESS;
}
Пример #3
0
/* Raw Servo Output Sender */
bool MAVLink::sendScaledServos(int16_t s1, int16_t s2, int16_t s3, int16_t s4, int16_t s5, int16_t s6, int16_t s7, int16_t s8, uint8_t rssi) {
	mavlink_message_t msg;
	mavlink_msg_rc_channels_scaled_pack(mySystemId,myComponentId,&msg,s1,s2,s3,s4,s5,s6,s7,s8,rssi);
	return sendMessage(msg);
}