Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support SkyViper V2450 #7539

Merged
merged 115 commits into from Feb 8, 2018
Merged

Support SkyViper V2450 #7539

merged 115 commits into from Feb 8, 2018

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Jan 15, 2018

This adds full support for the SkyViper 2450. It incorporates driver changes (some of which have separate PRs), plus additions to ArduCopter, new temperature calibration code and new declination code.
To build this firmware use:
./waf configure --board skyviper-v2450
it builds under ChibiOS

@rmackay9
Copy link
Contributor

Looks like it's failing travis because "degrees C" appears in the parameter descriptions..

// @DisplayName: Compass per-motor4 Z
// @Description: Compensation for Z axis of motor4
// @User: Advanced
AP_GROUPINFO("4", 6, Compass_PerMotor, compensation[3], 0),
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

compass compensation per-motor is limited to 4 motors?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes, for now, happy to extend it if there is demand

}

// this currently assumes first 4 channels.
uint16_t pwm = hal.rcout->read_last_sent(motor_map[motor]);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

assume is a lot like "TODO", is this safe-in-practice?

class Compass;

// per-motor compass compensation class. Currently tied to quadcopters
// only, and single magnetometer
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe raise this known limitation as an issue for future revisit ?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

worth discussing on a dev call

}

// set the 2.4GHz wifi channel used by companion computer, so it can be avoided
void AP_Radio::set_wifi_channel(uint8_t channel)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is more of a "avoid_wifi_channel" or "set_wifi_channel_to_avoid" than "set_wifi_channel", causual observer/s might think this function uses the wifi channel.

virtual void start_recv_bind(void) = 0;

// return time in microseconds of last received R/C packet
virtual uint32_t last_recv_us(void) = 0;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A uint32 counting microseconds will be able to count up to about 35 minutes. It's common for people to power up some of their equipment but not all of it (such as while waiting for gps lock, or making coffee). Is this going to potentially wrap-around if the TX is left turned off for more than ~35minutes.. ?

}
#endif

if (now - last_pps_ms > 1000) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hardcoded threshold of 1000 , maybe a #define, or a parameter?


// handle a data96 mavlink packet for fw upload
void AP_Radio_cc2500::handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
{
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

not impl, clearly.

bindTxId[1] = info.bindTxId[1];
bindOffset = info.bindOffset;
listLength = info.listLength;
memcpy(bindHopData, info.bindHopData, sizeof(bindHopData));
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

After blindly memcpy()-ing a chunk of data from ( possiby unreliable) storage into this struct, is it worth defensively checking to make sure that the data is 'good' before we trust it?

sizeof(_irq_handler_wa),
TIMEOUT_PRIORITY, /* Initial priority. */
irq_handler_thd, /* Thread function. */
NULL); /* Thread parameter. */
Copy link
Collaborator

@davidbuzz davidbuzz Jan 17, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I thought the point of the 'hal' was to hide this sort of OS specific thing from the ArduPilot code. Maybe this chibios "virtual timer" chVTObjectInit and 'Thread' chThdCreateStatic activities should be put in a hal->timer() or hal->thread() or something less platform specific?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes indeed - and Sid has some patches to add APIs for this

dsm.num_channels = MAX(dsm.num_channels, ch);
}

if (now - last_debug_print_ms > 1000) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

another hardcoded 1000 value, see earlier comment on a #define or parameter?

stm32_gpiosetevent(CYRF_IRQ_INPUT, true, false, false, irq_radio_trampoline);
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, HAL_GPIO_INTERRUPT_RISING);
#endif
Copy link
Collaborator

@davidbuzz davidbuzz Jan 17, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is another one of those cases where a hal should mean this block of #if code wouldn't be necerssary.
Can't hal->attach_interrupt(....) be made smart enough to know if it's on px4, and then call stm32_gpiosetevent behind the scenes?

hrt_call_after(&wait_call, 10000, (hrt_callout)irq_timeout_trampoline, nullptr);
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
//Note: please review Frequency in chconf.h to ensure the range of wait
chVTSet(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can these #ifdefs be moved into the hal-> ?

@davidbuzz
Copy link
Collaborator

I have reviewd, and put in a bunch of inline comments. but it's a +1 from me here for merge.

@tridge tridge force-pushed the chibios-skyviper branch 2 times, most recently from 8e414a8 to a04532a Compare January 17, 2018 08:50
@WickedShell
Copy link
Contributor

@tridge It looks like this include the per-motor compass stuff which is already a it's own PR #6448 and has open review comments that don't seem to be addressed in this PR either. Just tagging it that there is some review that was done from a different location on that part of this.

@tridge tridge force-pushed the chibios-skyviper branch 6 times, most recently from 2864eb6 to 955abde Compare January 20, 2018 06:41
@rmackay9
Copy link
Contributor

I know it's slightly bad behaviour but I plucked out the flight mode channel change into master. I did this because a user was pinging me about it so it gave me the opportunity to say, "it's done!".
8967448

Sadly, I slightly modified the commit to remove the addition of the #define for TOY_MODE. Sorry, I probably should have left that part in to avoid the merge conflict but I didn't for some reason.

@tridge tridge force-pushed the chibios-skyviper branch 2 times, most recently from 94a56af to 7748a28 Compare February 6, 2018 23:29
tridge and others added 27 commits February 8, 2018 17:04
this allows it to be used for a wide range of loop rates
on I2C the lower bus bandwidth changes the tradeoffs
these were unusued but still allocated
needed for good scheduling with I2C IMU
different button mapping for new controller
may be needed on other boards in the future, but for now we only know
its needed on an I2C 20789, which is rare
this adds FHLD_* parameters for FlowHold mode. It is a large patch as
it needs to disentagle the mode class to enable it to be used in
Parameters.h
@tridge tridge merged commit 88d53aa into ArduPilot:master Feb 8, 2018
@tridge
Copy link
Contributor Author

tridge commented Feb 8, 2018

merged after discussion with Randy
many thanks for input today from Peter, Randy and Michael

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

7 participants