mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
clang-tidy: partially fix readability-redundant-declaration
This commit is contained in:
@@ -93,8 +93,8 @@ Checks: '*,
|
|||||||
-readability-inconsistent-declaration-parameter-name,
|
-readability-inconsistent-declaration-parameter-name,
|
||||||
-readability-named-parameter,
|
-readability-named-parameter,
|
||||||
-readability-non-const-parameter,
|
-readability-non-const-parameter,
|
||||||
-readability-redundant-control-flow,
|
|
||||||
-readability-redundant-declaration,
|
-readability-redundant-declaration,
|
||||||
|
-readability-redundant-control-flow,
|
||||||
-readability-static-accessed-through-instance,
|
-readability-static-accessed-through-instance,
|
||||||
-readability-static-definition-in-anonymous-namespace,
|
-readability-static-definition-in-anonymous-namespace,
|
||||||
'
|
'
|
||||||
|
|||||||
@@ -38,8 +38,6 @@
|
|||||||
#include <queue.h>
|
#include <queue.h>
|
||||||
#include <stddef.h>
|
#include <stddef.h>
|
||||||
|
|
||||||
__EXPORT void sq_rem(sq_entry_t *node, sq_queue_t *queue);
|
|
||||||
sq_entry_t *sq_remafter(sq_entry_t *node, sq_queue_t *queue);
|
|
||||||
void sq_rem(sq_entry_t *node, sq_queue_t *queue)
|
void sq_rem(sq_entry_t *node, sq_queue_t *queue)
|
||||||
{
|
{
|
||||||
if (queue->head && node) {
|
if (queue->head && node) {
|
||||||
@@ -83,7 +81,6 @@ sq_entry_t *sq_remafter(sq_entry_t *node, sq_queue_t *queue)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
__EXPORT void sq_addfirst(sq_entry_t *node, sq_queue_t *queue);
|
|
||||||
void sq_addfirst(sq_entry_t *node, sq_queue_t *queue)
|
void sq_addfirst(sq_entry_t *node, sq_queue_t *queue)
|
||||||
{
|
{
|
||||||
node->flink = queue->head;
|
node->flink = queue->head;
|
||||||
|
|||||||
@@ -72,10 +72,8 @@ static LockstepScheduler *lockstep_scheduler = new LockstepScheduler();
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
hrt_abstime hrt_absolute_time_offset();
|
|
||||||
static void hrt_call_reschedule();
|
static void hrt_call_reschedule();
|
||||||
static void hrt_call_invoke();
|
static void hrt_call_invoke();
|
||||||
__EXPORT hrt_abstime hrt_reset();
|
|
||||||
|
|
||||||
hrt_abstime hrt_absolute_time_offset()
|
hrt_abstime hrt_absolute_time_offset()
|
||||||
{
|
{
|
||||||
@@ -463,11 +461,6 @@ void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callo
|
|||||||
hrt_call_internal(entry, calltime, 0, callout, arg);
|
hrt_call_internal(entry, calltime, 0, callout, arg);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
* Convert absolute time to a timespec.
|
|
||||||
*/
|
|
||||||
void abstime_to_ts(struct timespec *ts, hrt_abstime abstime);
|
|
||||||
|
|
||||||
static void
|
static void
|
||||||
hrt_call_invoke()
|
hrt_call_invoke()
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -102,13 +102,6 @@ int fixedwing_control_thread_main(int argc, char *argv[]);
|
|||||||
*/
|
*/
|
||||||
static void usage(const char *reason);
|
static void usage(const char *reason);
|
||||||
|
|
||||||
int parameters_init(struct param_handles *h);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Update all parameters
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
int parameters_update(const struct param_handles *h, struct params *p);
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Control roll and pitch angle.
|
* Control roll and pitch angle.
|
||||||
|
|||||||
@@ -56,8 +56,6 @@
|
|||||||
# error load_mon support requires CONFIG_SCHED_INSTRUMENTATION
|
# error load_mon support requires CONFIG_SCHED_INSTRUMENTATION
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern struct system_load_s system_load;
|
|
||||||
|
|
||||||
#define STACK_LOW_WARNING_THRESHOLD 300 ///< if free stack space falls below this, print a warning
|
#define STACK_LOW_WARNING_THRESHOLD 300 ///< if free stack space falls below this, print a warning
|
||||||
#define FDS_LOW_WARNING_THRESHOLD 3 ///< if free file descriptors fall below this, print a warning
|
#define FDS_LOW_WARNING_THRESHOLD 3 ///< if free file descriptors fall below this, print a warning
|
||||||
|
|
||||||
|
|||||||
@@ -85,8 +85,6 @@ static Mavlink *_mavlink_instances = nullptr;
|
|||||||
*/
|
*/
|
||||||
extern "C" __EXPORT int mavlink_main(int argc, char *argv[]);
|
extern "C" __EXPORT int mavlink_main(int argc, char *argv[]);
|
||||||
|
|
||||||
extern mavlink_system_t mavlink_system;
|
|
||||||
|
|
||||||
void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length)
|
void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length)
|
||||||
{
|
{
|
||||||
Mavlink *m = Mavlink::get_instance(chan);
|
Mavlink *m = Mavlink::get_instance(chan);
|
||||||
|
|||||||
Reference in New Issue
Block a user