Сообщение от erohin
Вечер добрый, подскажите как в прошивке MultiWii_2_1_b3 переназначить сумарный PPM с входа RX на THROTTLE, плата контроллера crius ALL IN ONE PRO v1.0 на меге 2560
отвечу на свой вопрос, разобрался такая возможность появилась в MultiWii dev version r1143 (2012/09/27)
необходимо отредактировать в
RX.ino после
/**************************************************************************************/
/*************** PPM SUM RX Pin reading ********************/
/**************************************************************************************/
// attachInterrupt fix for promicro
#if defined(PROMICRO) && defined(SERIAL_SUM_PPM)
ISR(INT6_vect){rxInt();}
#endif
вписать
#if defined(PPM_ON_THROTTLE) && defined(MEGA) && defined(SERIAL_SUM_PPM)
ISR(PCINT2_vect) { if(PINK & (1<<0)) rxInt(); }
#endif
затем в def.h в
/************************** all the Mega types ***********************************/
найти #define PPM_PIN_INTERRUPT attachInterrupt(4, rxInt, RISING); //PIN 19, also used for Spektrum satellite option
и заменить на
#if defined(PPM_ON_THROTTLE)
//configure THROTTLE PIN (A8 pin) as input witch pullup and enabled PCINT interrupt
#define PPM_PIN_INTERRUPT DDRK &= ~(1<<0); PORTK |= (1<<0); PCMSK2 |= (1<<0); PCICR |= (1<<2);
#else
#define PPM_PIN_INTERRUPT attachInterrupt(4, rxInt, RISING); //PIN 19, also used for Spektrum satellite option
#endif
и последнее в config.h после раскоменченного желаемого PPM дописать #define PPM_ON_THROTTLE
например так
/**************************************************************************************/
/******** special receiver types ********************/
/**************************************************************************************/
/**************************** PPM Sum Reciver ***********************************/
/* The following lines apply only for specific receiver with only one PPM sum signal, on digital PIN 2
Select the right line depending on your radio brand. Feel free to modify the order in your PPM order is different */
//#define SERIAL_SUM_PPM PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,AUX3,AUX4 //For Graupner/Spektrum
//#define SERIAL_SUM_PPM ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4 //For Robe/Hitec/Futaba
#define SERIAL_SUM_PPM PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4 //For some Hitec/Sanwa/Others
#define PPM_ON_THROTTLE
проверил работает.
ну както так...
Управление камерой по одной оси
Столкнулся с такой фигнёй:
Если включить управление подвесом - то каналы AUX3 и AUX4 - автоматом мапятся на поворот камеры по питчу и роллу соответственно. (вообще, на AIOP есть специальные пины под это дело, но они походу не используются). У меня на AUX3 висит переключение режимов. Соответственно, при щелчке переключателем камера поворачивается хрен-те-куда.
Мне это не понравилось, сделал вот такое решение, может быть кому-то окажется полезно:
config.h
/* Camstab pitch control only by one channel, uncomment only one option. Roll control is disabled.
E.g. CAM_STAB_AUX4_ONLY means that signal from AUX4 used to control pitch of the gimbal and AUX3 is ignored.
=== affects Output.ino - Cam stabilize Sevos section === */
// #define CAM_STAB_AUX3_ONLY
#define CAM_STAB_AUX4_ONLY
{"assets_hash":"a8b26fa7f6e768b07a72c8c9aadb9422","page_data":{"users":{"497ec4283df9550077772a70":{"_id":"497ec4283df9550077772a70","hid":43414,"name":"gorbln","nick":"gorbln","avatar_id":null,"css":""},"504834073df9550077740302":{"_id":"504834073df9550077740302","hid":125074,"name":"Alex_dndz","nick":"Alex_dndz","avatar_id":null,"css":""}},"settings":{"blogs_can_create":false,"blogs_mod_can_delete":false,"blogs_mod_can_hard_delete":false,"blogs_mod_can_add_infractions":false,"can_report_abuse":false,"can_vote":false,"can_see_ip":false,"blogs_edit_comments_max_time":30,"blogs_show_ignored":false,"blogs_reply_old_comment_threshold":30,"votes_add_max_time":168},"entry":{"_id":"515d324c997073007710b61c","hid":16615,"title":"Некоторые настройки Multiwii (будет дополняться)","html":"<p><strong data-nd-pair-src=\"**\">SUM PPM on THROTTLE</strong></p>\n<!--cut-->\n<pre class=\"hljs\"><code> Сообщение от erohin \n Вечер добрый, подскажите как в прошивке MultiWii_2_1_b3 переназначить сумарный PPM с входа RX на THROTTLE, плата контроллера crius ALL IN ONE PRO v1.0 на меге 2560\n отвечу на свой вопрос, разобрался такая возможность появилась в MultiWii dev version r1143 (2012/09/27)\nнеобходимо отредактировать в\nRX.ino после\n/**************************************************************************************/\n/*************** PPM SUM RX Pin reading ********************/\n/**************************************************************************************/\n// attachInterrupt fix for promicro\n#if defined(PROMICRO) && defined(SERIAL_SUM_PPM)\n ISR(INT6_vect){rxInt();}\n#endif\n\nвписать\n\n#if defined(PPM_ON_THROTTLE) && defined(MEGA) && defined(SERIAL_SUM_PPM)\n ISR(PCINT2_vect) { if(PINK & (1<<0)) rxInt(); }\n#endif\n\nзатем в def.h в\n/************************** all the Mega types ***********************************/\nнайти #define PPM_PIN_INTERRUPT attachInterrupt(4, rxInt, RISING); //PIN 19, also used for Spektrum satellite option\nи заменить на\n #if defined(PPM_ON_THROTTLE)\n //configure THROTTLE PIN (A8 pin) as input witch pullup and enabled PCINT interrupt\n #define PPM_PIN_INTERRUPT DDRK &= ~(1<<0); PORTK |= (1<<0); PCMSK2 |= (1<<0); PCICR |= (1<<2);\n #else\n #define PPM_PIN_INTERRUPT attachInterrupt(4, rxInt, RISING); //PIN 19, also used for Spektrum satellite option\n #endif\n\nи последнее в config.h после раскоменченного желаемого PPM дописать #define PPM_ON_THROTTLE\n\nнапример так\n\n/**************************************************************************************/\n /******** special receiver types ********************/\n /**************************************************************************************/\n /**************************** PPM Sum Reciver ***********************************/\n /* The following lines apply only for specific receiver with only one PPM sum signal, on digital PIN 2\n Select the right line depending on your radio brand. Feel free to modify the order in your PPM order is different */\n //#define SERIAL_SUM_PPM PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,AUX3,AUX4 //For Graupner/Spektrum\n //#define SERIAL_SUM_PPM ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4 //For Robe/Hitec/Futaba\n #define SERIAL_SUM_PPM PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4 //For some Hitec/Sanwa/Others\n #define PPM_ON_THROTTLE\n\nпроверил работает.\nну както так...\n</code></pre>\n<p><strong data-nd-pair-src=\"**\"><br>\nУправление камерой по одной оси</strong></p>\n<blockquote class=\"quote\" cite=\"https://rcopen.com/forum/f123/topic221574/6638\"><footer class=\"quote__title\"><div class=\"quote__controls float-end\"><button class=\"quote__expand btn btn-sm icon icon-expand\" data-i18n-title=\"expand\"></button><button class=\"quote__collapse btn btn-sm icon icon-collapse\" data-i18n-title=\"collapse\"></button><a class=\"quote__ref-local btn btn-sm icon icon-ref-local\" href=\"https://rcopen.com/forum/f123/topic221574/6638\" data-i18n-title=\"jump\"></a><a class=\"quote__ref-outer btn btn-sm icon icon-ref-outer\" href=\"https://rcopen.com/forum/f123/topic221574/6638\" data-i18n-title=\"jump\"></a></div><cite class=\"quote__author\"><img class=\"quote__author-avatar _identicon\" src=\"data:image/gif;base64,R0lGODlhAQABAIAAAAAAAP///yH5BAEAAAAALAAAAAABAAEAAAIBRAA7\" data-user-id=\"497ec4283df9550077772a70\" data-avatar-size=\"sm\"><span class=\"quote__author-name\" data-user-id=\"497ec4283df9550077772a70\">gorbln</span></cite>:</footer><div class=\"quote__content\">\n<p>Столкнулся с такой фигнёй:<br>\nЕсли включить управление подвесом - то каналы AUX3 и AUX4 - автоматом мапятся на поворот камеры по питчу и роллу соответственно. (вообще, на AIOP есть специальные пины под это дело, но они походу не используются). У меня на AUX3 висит переключение режимов. Соответственно, при щелчке переключателем камера поворачивается хрен-те-куда.<br>\nМне это не понравилось, сделал вот такое решение, может быть кому-то окажется полезно:<br>\nconfig.h</p>\n<pre class=\"hljs\"><code> /* Camstab pitch control only by one channel, uncomment only one option. Roll control is disabled.\n E.g. CAM_STAB_AUX4_ONLY means that signal from AUX4 used to control pitch of the gimbal and AUX3 is ignored.\n === affects Output.ino - Cam stabilize Sevos section === */\n // #define CAM_STAB_AUX3_ONLY\n #define CAM_STAB_AUX4_ONLY\n</code></pre>\n<p>output.ino<br>\nсначала надо удалить кусок</p>\n<pre class=\"hljs\"><code>S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX3]-1500;\n S_ROLL = TILT_ROLL_MIDDLE + rcData[AUX4]-1500;\n</code></pre>\n<p>и потом добавить</p>\n<pre class=\"hljs\"><code>#if defined(CAM_STAB_AUX3_ONLY)\n S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX3]-1500;\n S_ROLL = TILT_ROLL_MIDDLE;\n #endif\n #if defined(CAM_STAB_AUX4_ONLY)\n S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX4]-1500;\n S_ROLL = TILT_ROLL_MIDDLE;\n #endif\n #if !defined(CAM_STAB_AUX3_ONLY) && !defined(CAM_STAB_AUX4_ONLY)\n S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX3]-1500;\n S_ROLL = TILT_ROLL_MIDDLE + rcData[AUX4]-1500;\n #endif\n</code></pre>\n</div></blockquote>\n","user":"504834073df9550077740302","ts":"2013-04-04T07:57:00.000Z","st":1,"cache":{"comment_count":0},"views":1459,"bookmarks":0,"votes":0},"subscription":null},"locale":"en-US","user_id":"000000000000000000000000","user_hid":0,"user_name":"","user_nick":"","user_avatar":null,"is_member":false,"settings":{"can_access_acp":false,"can_use_dialogs":false,"hide_heavy_content":false},"unread_dialogs":false,"footer":{"rules":{"to":"common.rules"},"contacts":{"to":"rco-nodeca.contacts"}},"navbar":{"tracker":{"to":"users.tracker","autoselect":false,"priority":10},"forum":{"to":"forum.index"},"blogs":{"to":"blogs.index"},"clubs":{"to":"clubs.index"},"market":{"to":"market.index.buy"}},"recaptcha":{"public_key":"6LcyTs0dAAAAADW_1wxPfl0IHuXxBG7vMSSX26Z4"},"layout":"common.layout"}