Browse Source

增加了ADC采样显示板子温度

danny wang 2 years ago
parent
commit
d5de39184d

+ 7 - 0
ArduSub/ArduSub.cpp

@@ -79,12 +79,15 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
 
 constexpr int8_t Sub::_failsafe_priorities[5];
 
+
 void Sub::setup()
 {
     // Load the default values of variables listed in var_info[]s
     AP_Param::setup_sketch_defaults();
 
     init_ardupilot();
+	
+	chan_adc= hal.analogin->channel(0);
 
     // initialise the main loop scheduler
     scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), MASK_LOG_PM);
@@ -150,6 +153,10 @@ void Sub::fast_loop()
 // 50 Hz tasks
 void Sub::fifty_hz_loop()
 {
+	
+
+
+
     // check pilot input failsafe
     failsafe_pilot_input_check();
 

+ 1 - 0
ArduSub/Sub.cpp

@@ -19,6 +19,7 @@
 #undef FORCE_VERSION_H_INCLUDE
 
 const AP_HAL::HAL& hal = AP_HAL::get_HAL();
+AP_HAL::AnalogSource* chan_adc;
 
 /*
   constructor for main Sub class

+ 4 - 0
ArduSub/Sub.h

@@ -880,4 +880,8 @@ public:
 };
 
 extern const AP_HAL::HAL& hal;
+
 extern Sub sub;
+
+extern AP_HAL::AnalogSource* chan_adc;
+

+ 33 - 0
ArduSub/UserCode.cpp

@@ -1,4 +1,10 @@
 #include "Sub.h"
+//const AP_HAL::HAL& hal = AP_HAL::get_HAL();
+extern const AP_HAL::HAL& hal;
+
+
+extern mavlink_rov_state_monitoring_t rov_message;
+
 
 #ifdef USERHOOK_INIT
 void Sub::userhook_init()
@@ -23,6 +29,33 @@ void Sub::userhook_50Hz()
     USBL_PowerSwitch();
 	getgain();
 	getyaw();
+
+	 float v  = chan_adc->voltage_average();
+
+	 
+	  chan_adc->set_pin(14);
+	 float temprature =0.0;
+	 if (v>2.58)
+	{
+		 temprature = -44.017*v + 112.64;
+	}else if(v>1.0){
+		temprature =-28.635*v + 72.616;
+	}else if(v>0.518){
+		temprature =-48.078*v + 91.882;
+	}else if(v>0.28){
+		temprature =-90.07*v + 113.38;
+	}else if(v>0.12){
+		temprature = -195.98*v + 141.46;
+	}
+	else{
+		temprature = 120;
+	}
+
+	rov_message.temp = temprature;
+
+
+
+     
 }
 #endif
 

BIN
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.pyc


BIN
libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.pyc


+ 9 - 9
libraries/GCS_MAVLink/GCS_Common.cpp

@@ -1030,21 +1030,21 @@ void GCS_MAVLINK::update_send()
 			
 			mav_motor_speed_back.Ltrack = 0;
 			mav_motor_speed_back.Rtrack =0;
-			mav_motor_speed_back.motor1 =(float)sub._telemetry[0].rpm;//uint32 rpm
-			mav_motor_speed_back.motor2 =(float)sub._telemetry[1].rpm;
-			mav_motor_speed_back.motor3 =(float)sub._telemetry[2].rpm;
-			mav_motor_speed_back.motor4 =(float)sub._telemetry[3].rpm;
-			mav_motor_speed_back.motor5 =(float)sub._telemetry[4].rpm;
-			mav_motor_speed_back.motor6 =(float)sub._telemetry[5].rpm;
+			mav_motor_speed_back.motor1 =(float)sub._telemetry[0].rpm/7;//uint32 rpm
+			mav_motor_speed_back.motor2 =(float)sub._telemetry[1].rpm/7;
+			mav_motor_speed_back.motor3 =(float)sub._telemetry[2].rpm/7;
+			mav_motor_speed_back.motor4 =(float)sub._telemetry[3].rpm/7;
+			mav_motor_speed_back.motor5 =(float)sub._telemetry[4].rpm/7;
+			mav_motor_speed_back.motor6 =(float)sub._telemetry[5].rpm/7;
 			mav_motor_speed_back.motor7 =0;
 			mav_motor_speed_back.motor8 =0;
 
 			rov_message.floodlight = sub.lights;
 			//pressure_level  在各个模式中已经赋值
-			rov_message.low_voltage = (float)sub._telemetry[0].voltage;;
-			rov_message.high_voltage = (float)sub._telemetry[1].voltage;//sub._telemetry[0].voltage;//电压
+			rov_message.low_voltage = (float)sub._telemetry[0].voltage/10;
+			rov_message.high_voltage = (float)sub._telemetry[1].voltage/10;//sub._telemetry[0].voltage;//电压
 			rov_message.deep =fabsf(sub.barometer.get_altitude());//深度
-			rov_message.temp = 0;
+			//rov_message.temp = 0;
 			rov_message.motor_block_flag =	0;
 			rov_message.motor_twine_flag[0] = 0;//(uint16_t)uavcan.thruster[0].error_count;//故障码?
 			rov_message.motor_twine_flag[1] = 0;//(uint16_t)uavcan.thruster[1].error_count;