PX4 Firmware
PX4 Autopilot Software http://px4.io
px4io.c File Reference

Top-level logic for the PX4IO module. More...

#include <px4_platform_common/px4_config.h>
#include "platform/cxxinitialize.h"
#include <stdio.h>
#include <stdbool.h>
#include <stdlib.h>
#include <errno.h>
#include <string.h>
#include <poll.h>
#include <signal.h>
#include <crc32.h>
#include <syslog.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
#include <perf/perf_counter.h>
#include <output_limit/output_limit.h>
#include <stm32_uart.h>
#include "px4io.h"
Include dependency graph for px4io.c:

Go to the source code of this file.

Macros

#define DEBUG
 
#define NUM_MSG   1
 
#define APP_SIZE_MAX   0xf000
 
#define APP_LOAD_ADDRESS   0x08001000
 

Functions

__EXPORT int user_start (int argc, char *argv[])
 
static void heartbeat_blink (void)
 
static void ring_blink (void)
 
static void update_mem_usage (void)
 
void atomic_modify_or (volatile uint16_t *target, uint16_t modification)
 
void atomic_modify_clear (volatile uint16_t *target, uint16_t modification)
 
void atomic_modify_and (volatile uint16_t *target, uint16_t modification)
 
void isr_debug (uint8_t level, const char *fmt,...)
 send a debug message to the console More...
 
static void show_debug_messages (void)
 
void schedule_reboot (uint32_t time_delta_usec)
 schedule a reboot in time_delta_usec microseconds More...
 
static void check_reboot (void)
 check for a scheduled reboot More...
 
static void calculate_fw_crc (void)
 

Variables

struct sys_state_s system_state
 
static struct hrt_call serial_dma_call
 
output_limit_t pwm_limit
 
float dt
 
static volatile uint32_t msg_counter
 
static volatile uint32_t last_msg_counter
 
static volatile uint8_t msg_next_out
 
static volatile uint8_t msg_next_in
 
static char msg [NUM_MSG][CONFIG_USART1_TXBUFSIZE]
 
static uint64_t reboot_time
 

Detailed Description

Top-level logic for the PX4IO module.

Author
Lorenz Meier loren.nosp@m.z@px.nosp@m.4.io

Definition in file px4io.c.

Macro Definition Documentation

◆ APP_LOAD_ADDRESS

#define APP_LOAD_ADDRESS   0x08001000

Referenced by calculate_fw_crc().

◆ APP_SIZE_MAX

#define APP_SIZE_MAX   0xf000

Referenced by calculate_fw_crc().

◆ DEBUG

#define DEBUG

Definition at line 62 of file px4io.c.

◆ NUM_MSG

#define NUM_MSG   1

Definition at line 88 of file px4io.c.

Referenced by isr_debug(), and show_debug_messages().

Function Documentation

◆ atomic_modify_and()

void atomic_modify_and ( volatile uint16_t *  target,
uint16_t  modification 
)

Definition at line 109 of file px4io.c.

References PX4_CRITICAL_SECTION.

◆ atomic_modify_clear()

void atomic_modify_clear ( volatile uint16_t *  target,
uint16_t  modification 
)

Definition at line 102 of file px4io.c.

References PX4_CRITICAL_SECTION.

Referenced by controls_tick(), mixer_handle_text(), mixer_tick(), and safety_check_button().

Here is the caller graph for this function:

◆ atomic_modify_or()

void atomic_modify_or ( volatile uint16_t *  target,
uint16_t  modification 
)

Definition at line 95 of file px4io.c.

References PX4_CRITICAL_SECTION.

Referenced by controls_tick(), dsm_port_input(), mixer_tick(), and safety_check_button().

Here is the caller graph for this function:

◆ calculate_fw_crc()

static void calculate_fw_crc ( void  )
static

Definition at line 262 of file px4io.c.

References APP_LOAD_ADDRESS, APP_SIZE_MAX, PX4IO_P_SETUP_CRC, and r_page_setup.

Referenced by user_start().

Here is the caller graph for this function:

◆ check_reboot()

static void check_reboot ( void  )
static

check for a scheduled reboot

Definition at line 254 of file px4io.c.

References hrt_absolute_time(), and reboot_time.

Referenced by user_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ heartbeat_blink()

static void heartbeat_blink ( void  )
static

Definition at line 176 of file px4io.c.

References LED_BLUE.

Referenced by user_start().

Here is the caller graph for this function:

◆ isr_debug()

void isr_debug ( uint8_t  level,
const char *  fmt,
  ... 
)

send a debug message to the console

Definition at line 120 of file px4io.c.

References msg, msg_counter, msg_next_in, NUM_MSG, PX4IO_P_SETUP_SET_DEBUG, and r_page_setup.

Referenced by mixer_handle_text(), mixer_handle_text_create_mixer(), mixer_tick(), registers_set_one(), and user_start().

Here is the caller graph for this function:

◆ ring_blink()

static void ring_blink ( void  )
static

Definition at line 183 of file px4io.c.

References counter, LED_RING, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, r_setup_arming, and r_status_flags.

Referenced by user_start().

Here is the caller graph for this function:

◆ schedule_reboot()

void schedule_reboot ( uint32_t  time_delta_usec)

schedule a reboot in time_delta_usec microseconds

schedule a reboot

Definition at line 246 of file px4io.c.

References hrt_absolute_time(), and reboot_time.

Referenced by registers_set_one().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ show_debug_messages()

static void show_debug_messages ( void  )
static

Definition at line 138 of file px4io.c.

References debug, last_msg_counter, msg, msg_counter, msg_next_out, and NUM_MSG.

Referenced by user_start().

Here is the caller graph for this function:

◆ update_mem_usage()

static void update_mem_usage ( void  )
static

Definition at line 158 of file px4io.c.

References hrt_absolute_time(), PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, PX4IO_P_STATUS_FREEMEM, r_page_status, r_setup_arming, and r_status_flags.

Referenced by user_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ user_start()

Variable Documentation

◆ dt

float dt

Definition at line 73 of file px4io.c.

Referenced by vmount::OutputBase::_calculate_output_angles(), TECS::_update_speed_states(), PositionControl::_velocityController(), SmoothZTest::accelerateDownwardFromBrake(), SmoothZTest::accelerateUpwardFromBrake(), SmoothZTest::brakeDownward(), SmoothZTest::brakeUpward(), MavlinkRateLimiter::check(), ECL_YawController::control_bodyrate(), ECL_WheelController::control_bodyrate(), ECL_RollController::control_bodyrate(), ECL_PitchController::control_bodyrate(), RoverPositionControl::control_position(), FixedwingPositionControl::control_position(), RoverPositionControl::control_velocity(), detect_orientation(), Ekf2::filter_altitude_ellipsoid(), frsky_telemetry_thread_main(), TerrainEstimator::get_velocity(), Ekf::gps_is_good(), Ekf::initialiseCovariance(), main(), mixer_set_failsafe(), mixer_tick(), motor_ramp_thread_main(), perf_count(), perf_end(), perf_set_elapsed(), pid_calculate(), positionError(), TerrainEstimator::predict(), landing_target_estimator::KalmanFilter::predict(), Ekf::predictCovariance(), Integrator::put(), matrix::Quaternion< Type >::Quaternion(), Ekf::reset_imu_bias(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), AttitudeEstimatorQ::Run(), GPS::run(), BlockLocalPositionEstimator::Run(), ECL_L1_Pos_Controller::set_dt(), control::Block::setDt(), RateControl::setFeedForwardGain(), PositionControl::setHoverThrust(), EstimatorInterface::setIMUData(), Takeoff::setSpoolupTime(), uORB::DeviceMaster::showTop(), PrecLand::slewrate(), MatrixTest::squareMatrixTests(), Battery::sumDischarged(), control::SuperBlock::SuperBlock(), Mavlink::task_main(), FixedwingPositionControl::tecs_update_pitch_throttle(), TEST_F(), WindEstimator::update(), launchdetection::CatapultLaunchMethod::update(), landing_target_estimator::LandingTargetEstimator::update(), MavlinkStream::update(), AttitudeEstimatorQ::update(), FixedwingPositionControl::update_desired_altitude(), TECS::update_vehicle_state_estimates(), RateControl::updateIntegral(), ManualSmoothingXY::updateMaxVelocity(), MixingOutput::updateOutputSlewrate(), user_start(), and landing_target_estimator::KalmanFilter::~KalmanFilter().

◆ last_msg_counter

volatile uint32_t last_msg_counter
static

Definition at line 80 of file px4io.c.

Referenced by show_debug_messages().

◆ msg

char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
static

Definition at line 89 of file px4io.c.

Referenced by MavlinkFtpTest::_bad_datasize_test(), MavlinkFtpTest::_burst_test(), MavlinkFtpTest::_send_receive_msg(), Simulator::actuator_controls_from_outputs(), UavcanGnssBridge::broadcast_from_orb(), build_eam_response(), build_gam_request(), build_gam_response(), build_gps_response(), LeddarOne::collect(), GPSDriverSBF::configure(), GPSDriverUBX::configureMessageRate(), BlinkM::fade_hsb(), BlinkM::fade_hsb_random(), BlinkM::fade_rgb(), BlinkM::fade_rgb_random(), BlinkM::get_firmware_version(), UavcanBatteryBridge::get_name(), UavcanFlowBridge::get_name(), UavcanBarometerBridge::get_name(), UavcanMagnetometerBridge::get_name(), UavcanGnssBridge::get_name(), BlinkM::get_rgb(), Mavlink::get_status(), MavlinkULog::handle_update(), MavlinkCommandSender::handle_vehicle_command(), GPS::handleInjectDataTopic(), isr_debug(), UavcanEscController::max_output_value(), mixer_handle_text(), PX4IO::mixer_send(), MK::mk_check_for_blctrl(), MK::mk_servo_locate(), MK::mk_servo_set(), MK::mk_servo_test(), BlinkM::play_script(), Simulator::poll_for_MAVLink_messages(), publish_gam_message(), BlinkM::read_script_line(), MavlinkReceiver::Run(), MavlinkStreamHighLatency2::send(), MavlinkStreamStatustext::send(), MavlinkStreamSysStatus::send(), MavlinkStreamHighresIMU::send(), MavlinkStreamScaledIMU::send(), MavlinkStreamScaledIMU2::send(), MavlinkStreamScaledIMU3::send(), MavlinkStreamAttitude::send(), MavlinkStreamAttitudeQuaternion::send(), MavlinkStreamVFRHUD::send(), MavlinkStreamGPSRawInt::send(), MavlinkStreamGPS2Raw::send(), MavlinkStreamSystemTime::send(), MavlinkStreamTimesync::send(), MavlinkStreamADSBVehicle::send(), MavlinkStreamUTMGlobalPosition::send(), MavlinkStreamCollision::send(), MavlinkStreamCameraTrigger::send(), MavlinkStreamCameraImageCaptured::send(), MavlinkStreamGlobalPositionInt::send(), MavlinkStreamOdometry::send(), MavlinkStreamLocalPositionNED::send(), MavlinkStreamEstimatorStatus::send(), MavlinkStreamAttPosMocap::send(), MavlinkStreamHomePosition::send(), MavlinkStreamServoOutputRaw< N >::send(), MavlinkStreamActuatorControlTarget< N >::send(), MavlinkStreamHILActuatorControls::send(), MavlinkStreamPositionTargetGlobalInt::send(), MavlinkStreamLocalPositionSetpoint::send(), MavlinkStreamAttitudeTarget::send(), MavlinkStreamRCChannels::send(), MavlinkStreamManualControl::send(), MavlinkStreamTrajectoryRepresentationWaypoints::send(), MavlinkStreamOpticalFlowRad::send(), MavlinkStreamNamedValueFloat::send(), MavlinkStreamDebug::send(), MavlinkStreamDebugVect::send(), MavlinkStreamDebugFloatArray::send(), MavlinkStreamNavControllerOutput::send(), MavlinkStreamCameraCapture::send(), MavlinkStreamDistanceSensor::send(), MavlinkStreamAltitude::send(), MavlinkStreamWind::send(), MavlinkStreamMountOrientation::send(), MavlinkStreamGroundTruth::send(), MavlinkStreamPing::send(), MavlinkStreamObstacleDistance::send(), Mavlink::send_autopilot_capabilites(), RGBLED::send_led_enable(), RGBLED_NPC5623C::send_led_rgb(), RGBLED::send_led_rgb(), MavlinkParametersManager::send_one(), MavlinkParametersManager::send_param(), Mavlink::send_protocol_version(), MavlinkParametersManager::send_uavcan(), GPSDriverUBX::sendMessage(), BlinkM::set_fade_speed(), BlinkM::set_rgb(), BlinkM::set_script(), show_debug_messages(), BlinkM::stop_script(), Mavlink::task_main(), UavcanEscController::update_outputs(), GPSDriverUBX::waitForAck(), RGBLED_NPC5623C::write(), px4::logger::Logger::write_add_logged_msg(), px4::logger::Logger::write_changed_parameters(), px4::logger::Logger::write_format(), px4::logger::Logger::write_formats(), px4::logger::Logger::write_info(), px4::logger::Logger::write_info_multiple(), px4::logger::Logger::write_info_template(), px4::logger::Logger::write_parameters(), and BlinkM::write_script_line().

◆ msg_counter

volatile uint32_t msg_counter
static

Definition at line 79 of file px4io.c.

Referenced by isr_debug(), and show_debug_messages().

◆ msg_next_in

volatile uint8_t msg_next_in
static

Definition at line 81 of file px4io.c.

Referenced by isr_debug().

◆ msg_next_out

volatile uint8_t msg_next_out
static

Definition at line 81 of file px4io.c.

Referenced by show_debug_messages().

◆ pwm_limit

output_limit_t pwm_limit

Definition at line 71 of file px4io.c.

Referenced by mixer_callback(), and mixer_tick().

◆ reboot_time

uint64_t reboot_time
static

Definition at line 241 of file px4io.c.

Referenced by check_reboot(), and schedule_reboot().

◆ serial_dma_call

struct hrt_call serial_dma_call
static

Definition at line 69 of file px4io.c.

Referenced by user_start().

◆ system_state

struct sys_state_s system_state

Definition at line 67 of file px4io.c.

Referenced by controls_init(), controls_tick(), mixer_tick(), registers_set(), and user_start().