APM:Libraries
Public Member Functions | List of all members
AP_HAL::BetterStream Class Referenceabstract

#include <BetterStream.h>

Inheritance diagram for AP_HAL::BetterStream:
[legend]

Public Member Functions

virtual void printf (const char *,...) FMT_PRINTF(2
 
virtual void virtual void vprintf (const char *, va_list)
 
void print (const char *str)
 
void println (const char *str)
 
virtual size_t write (uint8_t)=0
 
virtual size_t write (const uint8_t *buffer, size_t size)
 
size_t write (const char *str)
 
virtual uint32_t available ()=0
 
virtual int16_t read ()=0
 
virtual uint32_t txspace ()=0
 

Detailed Description

Definition at line 27 of file BetterStream.h.

Member Function Documentation

◆ available()

virtual uint32_t AP_HAL::BetterStream::available ( )
pure virtual

Implemented in HALSITL::UARTDriver, F4Light::UARTDriver, ChibiOS::UARTDriver, BufferPrinter, F4Light::USBDriver, F4Light::UART_PPM, F4Light::UART_OSD, Linux::UARTDriver, PX4::PX4UARTDriver, VRBRAIN::VRBRAINUARTDriver, Empty::UARTDriver, PX4::NSHShellStream, and VRBRAIN::NSHShellStream.

Referenced by Menu::_check_for_input(), _read(), AP_GPS_SBP::_sbp_process(), AP_GPS_SBP2::_sbp_process(), AP_Proximity_LightWareSF40C::check_for_reply(), comm_get_available(), HAL_F4Light::connect_uart(), AP_RangeFinder_uLanding::detect_version(), drive(), AP_RangeFinder_LightWareSerial::get_reading(), AP_RangeFinder_MaxsonarSerialLV::get_reading(), AP_RangeFinder_uLanding::get_reading(), AP_RangeFinder_Benewake::get_reading(), AP_RangeFinder_Wasp::get_reading(), AP_RangeFinder_NMEA::get_reading(), AP_RangeFinder_LeddarOne::get_reading(), AP_Proximity_RPLidarA2::get_readings(), getch(), GCS_MAVLINK::handle_serial_control(), loop(), AP_RangeFinder_LeddarOne::parse_response(), println(), AP_GPS_NOVA::read(), AP_GPS_ERB::read(), AP_GPS_MTK::read(), AP_GPS_SIRF::read(), AP_GPS_GSOF::read(), AP_GPS_MTK19::read(), AP_GPS_SBF::read(), AP_GPS_NMEA::read(), AP_GPS_UBLOX::read(), AP_Mount_SToRM32_serial::read_incoming(), AP_Mount_Alexmos::read_incoming(), AP_Proximity_TeraRangerTower::read_sensor_data(), run_test(), AP_Frsky_Telem::send_SPort(), AP_Frsky_Telem::send_SPort_Passthrough(), AP_Beacon_Pozyx::update(), and AP_Beacon_Marvelmind::update().

Here is the caller graph for this function:

◆ print()

void AP_HAL::BetterStream::print ( const char *  str)
inline

Definition at line 33 of file BetterStream.h.

Here is the call graph for this function:

◆ printf()

void AP_HAL::BetterStream::printf ( const char *  fmt,
  ... 
)
virtual

Definition at line 5 of file BetterStream.cpp.

Referenced by AP_InertialSensor::_acal_save_calibrations(), Linux::CameraSensor_Mt9v117::_apply_patch(), AP_InertialSensor::_calculate_trim(), Linux::RCInput_SoloLink::_check_hdr(), AP_Compass_LSM9DS1::_check_id(), AP_Baro_LPS2XH::_check_whoami(), Linux::CameraSensor_Mt9v117::_config_change(), AP_InertialSensor_BMI160::_configure_fifo(), AP_InertialSensor_BMI160::_configure_int1_pin(), AP_ADC_ADS1115::_convert_register_data_to_mv(), Linux::VideoIn::_dequeue_frame(), Compass::_detect_backends(), Menu::_display_prompt(), AP_Compass_LSM9DS1::_dump_registers(), Linux::GPIO_Sysfs::_export_pin(), ChibiOS::Storage::_flash_load(), ChibiOS::Storage::_flash_write_data(), AP_Compass_LSM303D::_hardware_init(), AP_InertialSensor_LSM9DS1::_hardware_init(), AP_InertialSensor_LSM9DS0::_hardware_init(), AP_InertialSensor_Invensense::_hardware_init(), Menu::_help(), AP_Baro_LPS2XH::_imu_i2c_init(), AP_InertialSensor_BMI160::_init(), AP_InertialSensor_RST::_init_accel(), VRBRAIN::VRBRAINRCOutput::_init_alt_channels(), PX4::PX4RCOutput::_init_alt_channels(), AP_InertialSensor_RST::_init_gyro(), AP_InertialSensor::_init_gyro(), AP_Compass_BMM150::_load_trim_values(), Linux::GPIO_Sysfs::_open_pin_value(), AP_GPS_UBLOX::_parse_gps(), Linux::GPIO_Sysfs::_pinMode(), Linux::VideoIn::_queue_buffer(), AP_InertialSensor_LSM9DS0::_read_data_transaction_a(), AP_InertialSensor_LSM9DS1::_read_data_transaction_g(), AP_InertialSensor_LSM9DS0::_read_data_transaction_g(), AP_InertialSensor_LSM9DS1::_read_data_transaction_x(), AP_InertialSensor_Invensense::_read_fifo(), AP_InertialSensor_BMI160::_read_fifo(), Linux::CameraSensor_Mt9v117::_read_reg16(), Linux::CameraSensor_Mt9v117::_read_reg8(), AP_Compass_LSM303D::_read_sample(), Menu::_run_command(), VRBRAIN::VRBRAINScheduler::_timer_thread(), PX4::PX4Scheduler::_timer_thread(), Linux::RCInput_UDP::_timer_tick(), HALSITL::UARTDriver::_uart_start_connection(), VRBRAIN::VRBRAINUARTDriver::_write_fd(), PX4::PX4UARTDriver::_write_fd(), Linux::CameraSensor_Mt9v117::_write_reg16(), Linux::CameraSensor_Mt9v117::_write_reg32(), Linux::CameraSensor_Mt9v117::_write_reg8(), Linux::VideoIn::allocate_buffers(), AP_RangeFinder_PX4_PWM::AP_RangeFinder_PX4_PWM(), AP_RPM_PX4_PWM::AP_RPM_PX4_PWM(), Linux::SPIUARTDriver::begin(), PX4::PX4UARTDriver::begin(), VRBRAIN::VRBRAINUARTDriver::begin(), Linux::Perf::begin(), AP_BoardConfig::board_autodetect(), AP_BoardConfig::board_setup_sbus(), AnalogIn_ADS1115::channel(), AnalogIn_Navio2::channel(), PX4::PX4AnalogIn::channel(), VRBRAIN::VRBRAINAnalogIn::channel(), ChibiOS::AnalogIn::channel(), check_path(), check_result(), AP_Param::convert_old_parameter(), Linux::Perf::count(), AP_RangeFinder_PX4_PWM::detect(), display_offsets_and_scaling(), drive(), Linux::PWM_Sysfs_Base::enable(), Linux::Perf::end(), SchedTest::five_second_call(), get_device(), ChibiOS::SPIDeviceManager::get_device(), Linux::PWM_Sysfs_Base::get_period(), Linux::PWM_Sysfs_Base::get_polarity(), MenuCommands::gpio_input_channel(), MenuCommands::gpio_output_channel(), Compass::handle_mag_cal_command(), GCS_MAVLINK::handle_preflight_reboot(), GCS_MAVLINK::handle_setup_signing(), ChibiOS::I2CDevice::I2CDevice(), AP_RAMTRON::init(), PX4::PX4RCOutput::init(), VRBRAIN::VRBRAINRCOutput::init(), Linux::RCInput_UDP::init(), AP_IRLock_SITL::init(), VRBRAIN::VRBRAINGPIO::init(), ToneAlarm_ChibiOS::init(), ToneAlarm_Linux::init(), AP_Compass_LSM9DS1::init(), AP_SBusOut::init(), ToneAlarm_PX4::init(), PX4::PX4GPIO::init(), OreoLED_PX4::init(), AP_Airspeed_SDP3X::init(), AP_Compass_BMM150::init(), AP_Compass_AK8963::init(), DataFlash_Class::Init(), AP_ADSB::init(), Linux::ToneAlarm::init(), AP_Avoidance::init(), MissionTest::init_mission(), MissionTest::init_mission_endless_loop(), MissionTest::init_mission_ends_with_do_commands(), MissionTest::init_mission_ends_with_jump_command(), MissionTest::init_mission_jump_to_nonnav(), MissionTest::init_mission_no_nav_commands(), MissionTest::init_mission_starts_with_do_commands(), inverse4x4(), Linux::PWM_Sysfs_Base::is_enabled(), AP_Param::load_object_from_eeprom(), GCS_MAVLINK::load_signing_key(), DataFlashTest_AllTypes::Log_Write_TypeMessages(), DataFlashTest_AllTypes::Log_Write_TypeMessages_Log_Write(), loop(), FlashTest::loop(), RC_UART::loop(), DataFlashTest::loop(), DataFlashTest_AllTypes::loop(), missing_rotations(), MissionTest::mission_complete(), motor_order_test(), SchedTest::one_hz_print(), Linux::VideoIn::open_device(), AP_Invensense_AuxiliaryBusSlave::passthrough_read(), AP_Invensense_AuxiliaryBusSlave::passthrough_write(), print_latlon(), MissionTest::print_mission(), print_pwm(), print_radio_values(), print_vector(), println(), AP_BoardConfig::px4_setup_pwm(), AP_BoardConfig::px4_setup_safety_mask(), PX4::PX4RCInput::rc_bind(), Linux::DigitalSource_Sysfs::read(), AP_GPS_MTK19::read(), Linux::GPIO_Sysfs::read(), AP_Invensense_AuxiliaryBusSlave::read(), readTemp(), Linux::Scheduler::register_io_process(), PX4::PX4Scheduler::register_io_process(), VRBRAIN::VRBRAINScheduler::register_io_process(), ChibiOS::Scheduler::register_io_process(), Linux::Scheduler::register_timer_process(), PX4::PX4Scheduler::register_timer_process(), VRBRAIN::VRBRAINScheduler::register_timer_process(), ChibiOS::Scheduler::register_timer_process(), PX4::PX4Util::run_debug_shell(), VRBRAIN::VRBRAINUtil::run_debug_shell(), MissionTest::run_max_cmd_test(), MissionTest::run_mission_test(), MissionTest::run_replace_cmd_test(), MissionTest::run_resume_test(), MissionTest::run_set_current_cmd_test(), MissionTest::run_set_current_cmd_while_stopped_test(), run_test(), SoloGimbalEKF::RunEKF(), AP_Param::save(), GCS_Dummy::send_statustext(), AP_Param::set_and_save_by_name(), SRV_Channels::set_aux_channel_default(), AnalogSource_Navio2::set_channel(), Linux::VideoIn::set_crop(), PX4::PX4RCOutput::set_failsafe_pwm(), VRBRAIN::VRBRAINRCOutput::set_failsafe_pwm(), Linux::VideoIn::set_format(), PX4::PX4RCOutput::set_freq(), VRBRAIN::VRBRAINRCOutput::set_freq(), ChibiOS::RCOutput::set_freq(), VRBRAIN::VRBRAINRCOutput::set_freq_fd(), PX4::PX4RCOutput::set_freq_fd(), VRBRAIN::VRBRAINRCOutput::set_output_mode(), PX4::PX4RCOutput::set_output_mode(), Linux::PWM_Sysfs_Base::set_period(), Linux::PWM_Sysfs_Base::set_polarity(), PX4::PX4RCOutput::set_safety_pwm(), VRBRAIN::VRBRAINRCOutput::set_safety_pwm(), setup(), MissionTest::setup(), FlashTest::setup(), RC_UART::setup(), DataFlashTest::setup(), DataFlashTest_AllTypes::setup(), AP_InertialSensor::simple_accel_cal(), HALSITL::Scheduler::sitl_end_atomic(), AP_BoardConfig::spi_check_register(), stability_test(), AP_InertialSensor_Invensense::start(), MissionTest::start_cmd(), VRBRAIN::NSHShellStream::start_shell(), PX4::NSHShellStream::start_shell(), test_accuracy(), test_conversion(), test_conversions(), test_euler(), test_eulers(), test_frame_transforms(), test_gpio_input(), test_gpio_output(), test_high_low_byte(), test_matrix_eulers(), test_matrix_inverse(), test_matrix_rotate(), test_one_offset(), test_passed_waypoint(), test_printf(), test_quaternion_eulers(), test_rotate_inverse(), test_rotate_matrix(), test_rotation_accuracy(), test_uart(), test_wgs_conversion_functions(), test_wrap_cd(), Linux::SPIDevice::transfer(), ChibiOS::I2CDevice::transfer(), ChibiOS::SPIDevice::transfer(), Linux::SPIDevice::transfer_fullduplex(), AP_InertialSensor_LSM9DS0::update(), AP_InertialSensor_LSM9DS1::update(), AP_SBusOut::update(), AP_OpticalFlow_Onboard::update(), SoloGimbal_Parameters::update(), AP_BoardConfig::validate_board_type(), MissionTest::verify_cmd(), AP_InertialSensor::wait_for_sample(), Linux::DigitalSource_Sysfs::write(), Linux::GPIO_Sysfs::write(), and ChibiOS::UARTDriver::write_pending_bytes().

Here is the call graph for this function:

◆ println()

void AP_HAL::BetterStream::println ( const char *  str)
inline

Definition at line 34 of file BetterStream.h.

Referenced by F4Light::Scheduler::reboot(), setup(), and AP_InertialSensor_LSM9DS1::update().

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

◆ read()

virtual int16_t AP_HAL::BetterStream::read ( )
pure virtual

Implemented in HALSITL::UARTDriver, F4Light::UARTDriver, ChibiOS::UARTDriver, BufferPrinter, F4Light::USBDriver, F4Light::UART_OSD, F4Light::UART_PPM, Linux::UARTDriver, PX4::PX4UARTDriver, VRBRAIN::VRBRAINUARTDriver, Empty::UARTDriver, PX4::NSHShellStream, and VRBRAIN::NSHShellStream.

Referenced by Menu::_check_for_input(), _read(), AP_GPS_SBP::_sbp_process(), AP_GPS_SBP2::_sbp_process(), AP_Proximity_LightWareSF40C::check_for_reply(), HAL_F4Light::connect_uart(), AP_GPS::detect_instance(), AP_RangeFinder_uLanding::detect_version(), AP_RangeFinder_LightWareSerial::get_reading(), AP_RangeFinder_MaxsonarSerialLV::get_reading(), AP_RangeFinder_uLanding::get_reading(), AP_RangeFinder_Benewake::get_reading(), AP_RangeFinder_Wasp::get_reading(), AP_RangeFinder_NMEA::get_reading(), AP_RangeFinder_LeddarOne::get_reading(), AP_Proximity_RPLidarA2::get_readings(), getch(), GCS_MAVLINK::handle_serial_control(), loop(), AP_RangeFinder_LeddarOne::parse_response(), println(), AP_GPS_ERB::read(), AP_GPS_NOVA::read(), AP_GPS_SIRF::read(), AP_GPS_MTK::read(), AP_GPS_MTK19::read(), AP_GPS_GSOF::read(), AP_GPS_SBF::read(), AP_GPS_NMEA::read(), AP_GPS_UBLOX::read(), AP_Mount_SToRM32_serial::read_incoming(), AP_Mount_Alexmos::read_incoming(), AP_Proximity_TeraRangerTower::read_sensor_data(), run_test(), AP_Frsky_Telem::send_SPort(), AP_Frsky_Telem::send_SPort_Passthrough(), AP_Beacon_Pozyx::update(), AP_Beacon_Marvelmind::update(), and GCS_MAVLINK::update().

Here is the caller graph for this function:

◆ txspace()

virtual uint32_t AP_HAL::BetterStream::txspace ( )
pure virtual

◆ vprintf()

void AP_HAL::BetterStream::vprintf ( const char *  fmt,
va_list  ap 
)
virtual

Definition at line 13 of file BetterStream.cpp.

Referenced by hal_console_vprintf(), printf(), and printf().

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

◆ write() [1/3]

virtual size_t AP_HAL::BetterStream::write ( uint8_t  )
pure virtual

Implemented in HALSITL::UARTDriver, F4Light::UARTDriver, ChibiOS::UARTDriver, F4Light::USBDriver, F4Light::UART_PPM, F4Light::UART_OSD, Linux::UARTDriver, PX4::PX4UARTDriver, VRBRAIN::VRBRAINUARTDriver, Empty::UARTDriver, BufferPrinter, PX4::NSHShellStream, and VRBRAIN::NSHShellStream.

Referenced by Menu::_check_for_input(), AP_GPS_UBLOX::_send_message(), AP_GPS_NOVA::AP_GPS_NOVA(), AP_GPS_SBF::AP_GPS_SBF(), comm_send_buffer(), HAL_F4Light::connect_uart(), AP_Mount_SToRM32_serial::get_angles(), AP_RangeFinder_LightWareSerial::get_reading(), AP_RangeFinder_LeddarOne::get_reading(), GCS_MAVLINK::handle_serial_control(), AP_GPS_NOVA::inject_data(), AP_GPS_SBP2::inject_data(), AP_GPS_SBP::inject_data(), AP_GPS_Backend::inject_data(), loop(), AP_GPS_SBF::mount_disk(), print(), print_vprintf(), println(), putch(), AP_GPS_NOVA::read(), AP_GPS_SBF::read(), AP_GPS_GSOF::requestBaud(), AP_GPS_GSOF::requestGSOF(), AP_Proximity_RPLidarA2::reset_rplidar(), AP_GPS::send_blob_update(), AP_Frsky_Telem::send_byte(), AP_Volz_Protocol::send_command(), AP_Mount_Alexmos::send_command(), AP_DEVO_Telem::send_frames(), AP_Proximity_LightWareSF40C::send_request_for_distance(), AP_Proximity_LightWareSF40C::send_request_for_health(), AP_Proximity_RPLidarA2::send_request_for_health(), AP_Mount_SToRM32_serial::send_target_angles(), AP_Frsky_Telem::send_uint16(), AP_Proximity_LightWareSF40C::set_forward_direction(), AP_Proximity_LightWareSF40C::set_motor_direction(), AP_Proximity_LightWareSF40C::set_motor_speed(), AP_Proximity_RPLidarA2::set_scan_mode(), GCS_MAVLINK::setup_uart(), AP_GPS_SBF::unmount_disk(), AP_RangeFinder_Wasp::update(), AP_SBusOut::update(), and write().

Here is the caller graph for this function:

◆ write() [2/3]

size_t AP_HAL::BetterStream::write ( const uint8_t *  buffer,
size_t  size 
)
virtual

Reimplemented in HALSITL::UARTDriver, F4Light::UARTDriver, ChibiOS::UARTDriver, F4Light::USBDriver, F4Light::UART_PPM, F4Light::UART_OSD, Linux::UARTDriver, PX4::PX4UARTDriver, VRBRAIN::VRBRAINUARTDriver, BufferPrinter, Empty::UARTDriver, PX4::NSHShellStream, and VRBRAIN::NSHShellStream.

Definition at line 18 of file BetterStream.cpp.

Here is the call graph for this function:

◆ write() [3/3]

size_t AP_HAL::BetterStream::write ( const char *  str)

Definition at line 28 of file BetterStream.cpp.

Here is the call graph for this function:

The documentation for this class was generated from the following files: