APM:Libraries
Macros | Typedefs | Functions | Variables
sd.c File Reference
#include "sd.h"
#include "../diskio.h"
#include "../ff.h"
#include <stdlib.h>
#include <stdint.h>
#include <syscalls.h>
Include dependency graph for sd.c:

Go to the source code of this file.

Macros

#define CS_HIGH()   spi_chipSelectHigh()
 
#define CS_LOW()   spi_chipSelectLow(1)
 
#define MMC_CD   spi_detect() /* Card detect (yes:true, no:false, default:true) */
 
#define MMC_WP   0 /* Write protected (yes:true, no:false, default:false) */
 
#define CMD0   (0) /* GO_IDLE_STATE */
 
#define CMD1   (1) /* SEND_OP_COND (MMC) */
 
#define ACMD41   (0x80+41) /* SEND_OP_COND (SDC) */
 
#define CMD8   (8) /* SEND_IF_COND */
 
#define CMD9   (9) /* SEND_CSD */
 
#define CMD10   (10) /* SEND_CID */
 
#define CMD12   (12) /* STOP_TRANSMISSION */
 
#define CMD13   (13) /* Get_STATUS */
 
#define ACMD13   (0x80+13) /* SD_STATUS (SDC) */
 
#define CMD16   (16) /* SET_BLOCKLEN */
 
#define CMD17   (17) /* READ_SINGLE_BLOCK */
 
#define CMD18   (18) /* READ_MULTIPLE_BLOCK */
 
#define CMD23   (23) /* SET_BLOCK_COUNT (MMC) */
 
#define ACMD23   (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */
 
#define CMD24   (24) /* WRITE_BLOCK */
 
#define CMD25   (25) /* WRITE_MULTIPLE_BLOCK */
 
#define CMD32   (32) /* ERASE_ER_BLK_START */
 
#define CMD33   (33) /* ERASE_ER_BLK_END */
 
#define CMD38   (38) /* ERASE */
 
#define CMD55   (55) /* APP_CMD */
 
#define CMD58   (58) /* READ_OCR */
 

Typedefs

typedef uint8_t(* spi_WaitFunc) (uint8_t b)
 

Functions

static uint32_t micros ()
 
static uint32_t millis ()
 
uint8_t spi_spiSend (uint8_t b)
 
uint8_t spi_spiRecv (void)
 
uint8_t spi_spiXchg (uint8_t b)
 
void spi_spiTransfer (const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)
 
void spi_chipSelectHigh (void)
 
bool spi_chipSelectLow (bool take_sem)
 
void spi_yield ()
 
uint8_t spi_waitFor (uint8_t out, spi_WaitFunc cb, uint32_t dly)
 
uint8_t spi_detect ()
 
uint32_t get_fattime ()
 
int printf (const char *msg,...)
 

Variables

static volatile DSTATUS Stat = STA_NOINIT
 
static volatile uint16_t Timer1
 
static volatile uint16_t Timer2
 
static uint32_t sd_max_sectors =0
 

Macro Definition Documentation

◆ ACMD13

#define ACMD13   (0x80+13) /* SD_STATUS (SDC) */

Definition at line 43 of file sd.c.

◆ ACMD23

#define ACMD23   (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */

Definition at line 48 of file sd.c.

◆ ACMD41

#define ACMD41   (0x80+41) /* SEND_OP_COND (SDC) */

Definition at line 37 of file sd.c.

◆ CMD0

#define CMD0   (0) /* GO_IDLE_STATE */

Definition at line 35 of file sd.c.

◆ CMD1

#define CMD1   (1) /* SEND_OP_COND (MMC) */

Definition at line 36 of file sd.c.

◆ CMD10

#define CMD10   (10) /* SEND_CID */

Definition at line 40 of file sd.c.

◆ CMD12

#define CMD12   (12) /* STOP_TRANSMISSION */

Definition at line 41 of file sd.c.

◆ CMD13

#define CMD13   (13) /* Get_STATUS */

Definition at line 42 of file sd.c.

◆ CMD16

#define CMD16   (16) /* SET_BLOCKLEN */

Definition at line 44 of file sd.c.

◆ CMD17

#define CMD17   (17) /* READ_SINGLE_BLOCK */

Definition at line 45 of file sd.c.

◆ CMD18

#define CMD18   (18) /* READ_MULTIPLE_BLOCK */

Definition at line 46 of file sd.c.

◆ CMD23

#define CMD23   (23) /* SET_BLOCK_COUNT (MMC) */

Definition at line 47 of file sd.c.

◆ CMD24

#define CMD24   (24) /* WRITE_BLOCK */

Definition at line 49 of file sd.c.

◆ CMD25

#define CMD25   (25) /* WRITE_MULTIPLE_BLOCK */

Definition at line 50 of file sd.c.

◆ CMD32

#define CMD32   (32) /* ERASE_ER_BLK_START */

Definition at line 51 of file sd.c.

◆ CMD33

#define CMD33   (33) /* ERASE_ER_BLK_END */

Definition at line 52 of file sd.c.

◆ CMD38

#define CMD38   (38) /* ERASE */

Definition at line 53 of file sd.c.

◆ CMD55

#define CMD55   (55) /* APP_CMD */

Definition at line 54 of file sd.c.

◆ CMD58

#define CMD58   (58) /* READ_OCR */

Definition at line 55 of file sd.c.

◆ CMD8

#define CMD8   (8) /* SEND_IF_COND */

Definition at line 38 of file sd.c.

◆ CMD9

#define CMD9   (9) /* SEND_CSD */

Definition at line 39 of file sd.c.

◆ CS_HIGH

#define CS_HIGH ( )    spi_chipSelectHigh()

Definition at line 20 of file sd.c.

◆ CS_LOW

#define CS_LOW ( )    spi_chipSelectLow(1)

Definition at line 21 of file sd.c.

◆ MMC_CD

#define MMC_CD   spi_detect() /* Card detect (yes:true, no:false, default:true) */

Definition at line 22 of file sd.c.

◆ MMC_WP

#define MMC_WP   0 /* Write protected (yes:true, no:false, default:false) */

Definition at line 23 of file sd.c.

Typedef Documentation

◆ spi_WaitFunc

typedef uint8_t(* spi_WaitFunc) (uint8_t b)

Definition at line 62 of file sd.c.

Function Documentation

◆ get_fattime()

uint32_t get_fattime ( )

◆ micros()

static uint32_t micros ( )
inlinestatic

Definition at line 58 of file sd.c.

Here is the call graph for this function:

◆ millis()

static uint32_t millis ( )
inlinestatic

Definition at line 60 of file sd.c.

Here is the call graph for this function:

◆ printf()

int printf ( const char *  msg,
  ... 
)

Definition at line 113 of file stdio.c.

Referenced by Linux::UtilRPI::_check_rpi_version(), AP_Compass_BMM150::_compensate_z(), AP_Compass_QMC5883L::_dump_registers(), EEPROMClass::_ErasePage(), AP_Compass_MAG3110::_hardware_init(), AP_Baro_MS56XX::_init(), AP_Baro_KellerLD::_init(), EEPROMClass::_init(), AP_InertialSensor_RST::_init_accel(), AP_InertialSensor_RST::_init_gyro(), PX4::PX4Storage::_mtd_load(), VRBRAIN::VRBRAINStorage::_mtd_load(), AP_InertialSensor_PX4::_new_accel_sample(), AP_InertialSensor_PX4::_new_gyro_sample(), HALSITL::SITL_State::_parse_command_line(), F4Light::Scheduler::_print_stats(), Linux::RCOutput_Bebop::_run_rcout(), HALSITL::SITL_State::_set_param_default(), Linux::VideoIn::_set_streaming(), PX4::PX4Storage::_storage_open(), VRBRAIN::VRBRAINStorage::_storage_open(), Linux::Scheduler::_timer_task(), VRBRAIN::VRBRAINScheduler::_timer_thread(), PX4::PX4Scheduler::_timer_thread(), F4Light::Scheduler::_try_kill_task_or_reboot(), HALSITL::SITL_State::_update_gps_file(), AP_TECS::_update_pitch(), AP_InertialSensor_Backend::_update_sensor_rate(), HALSITL::SITL_State::_usage(), _usage(), OSD_EEPROM::_write(), Linux::RCInput::add_dsm_input(), Linux::RCInput::add_sbus_input(), SITL::Aircraft::Aircraft(), Linux::VideoIn::allocate_buffers(), ap_hook_accel_sample(), ap_hook_AHRS_update(), ap_hook_gyro_sample(), ap_hook_setup_complete(), ap_hook_setup_start(), AP_BoardConfig::board_setup_drivers(), AP_Airspeed_MS5525::calculate(), MAVLink_routing::check_and_forward(), AP_RangeFinder_VL53L0X::check_id(), AP_HAL::Device::check_next_register(), GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(), AP_Param::count_embedded_param_defaults(), PX4::PX4Scheduler::delay(), VRBRAIN::VRBRAINScheduler::delay(), AP_GPS::detect_instance(), dsm_decode(), SITL::FlightAxis::exchange_data(), Linux::SPIDeviceManager::get_device(), PX4::SPIDeviceManager::get_device(), VRBRAIN::SPIDeviceManager::get_device(), ChibiOS::SPIDeviceManager::get_device(), F4Light::Scheduler::get_next_task(), MAVLink_routing::handle_heartbeat(), AP_IRLock_I2C::init(), TSYS01::init(), AP_Baro_DPS280::init(), AP_Baro_FBM320::init(), Linux::RCOutput_Disco::init(), AP_RangeFinder_VL53L0X::init(), Linux::Led_Sysfs::init(), Linux::RCInput_SBUS::init(), AP_Airspeed_MS4525::init(), AP_RangeFinder_PulsedLightLRF::init(), AP_Airspeed_MS5525::init(), AP_Compass_IST8310::init(), AP_Compass_QMC5883L::init(), AP_Compass_LIS3MDL::init(), AP_Compass_MMC3416::init(), DataFlash_Class::Init(), AP_Compass_AK09916::init(), Linux::GPIO_BBB::init(), AP_Gripper_EPM::init_gripper(), HAL_F4Light::lateInit(), MAVLink_routing::learn_route(), loop(), main(), Linux::RCInput_RPI::map_peripheral(), SITL::MultiCopter::MultiCopter(), TCPServerDevice::open(), SITL::JSBSim::open_control_socket(), param_find(), SITL::Aircraft::parse_home(), AP_Param::parse_param_line(), SITL::FlightAxis::parse_reply(), perror(), AP_BoardConfig::px4_setup_peripherals(), AP_BoardConfig::px4_setup_px4io(), AP_BoardConfig::px4_start_driver(), SITL::QuadPlane::QuadPlane(), F4Light::RCInput::read(), AP_Compass_LIS3MDL::read(), read_calibration_data(), AP_IRLock_I2C::read_frames(), Linux::RCOutput_Bebop::read_obs_data(), AP_Airspeed_MS5525::read_prom(), SITL::XPlane::receive_data(), AP_Param::reload_defaults_file(), SITL::FlightAxis::report_FPS(), HAL_Linux::run(), HAL_PX4::run(), HAL_VRBRAIN::run(), HAL_F4Light::run(), AP_OpticalFlow_PX4Flow::scan_buses(), SCSI_ProcessCmd(), sdcard_init(), SITL::XPlane::select_data(), SITL::ADSB::send_report(), SITL::Gimbal::send_report(), MAVLink_routing::send_to_components(), AP_BoardConfig::sensor_config_error(), AP_HAL::Device::set_checked_register(), Linux::RCInput_SBUS::set_device_path(), SITL::Gazebo::set_interface_ports(), set_object_value_and_report(), FlashTest::setup(), setup(), show_matrix(), SITL::SimRover::SimRover(), SITL::Aircraft::smooth_sensors(), SITL::FlightAxis::soap_request(), PX4::SPIDevice::SPIDevice(), VRBRAIN::SPIDevice::SPIDevice(), srxl_channels_get_v5(), srxl_decode(), DataFlash_MAVLink::stats_log(), sumd_decode(), Linux::Scheduler::suspend_timer_procs(), SITL::Aircraft::sync_frame_time(), test_matrix_inverse(), AP_Compass_QMC5883L::timer(), AP_Compass_MMC3416::timer(), type_size(), SITL::Tracker::update(), SITL::Balloon::update(), SITL::XPlane::update(), SITL::Sprayer::update(), SITL::ICEngine::update(), SITL::Aircraft::update_dynamics(), SITL::Gripper_EPM::update_from_demand(), AP_TECS::update_pitch_throttle(), SITL::Vicon::update_vicon_position_estimate(), usage(), Soft_I2C::wait_done(), FlashTest::write(), SITL::XPlane::XPlane(), AP_HAL::yield(), PX4::I2CDevice::~I2CDevice(), VRBRAIN::I2CDevice::~I2CDevice(), ChibiOS::I2CDevice::~I2CDevice(), PX4::SPIDevice::~SPIDevice(), and VRBRAIN::SPIDevice::~SPIDevice().

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

◆ spi_chipSelectHigh()

void spi_chipSelectHigh ( void  )

◆ spi_chipSelectLow()

bool spi_chipSelectLow ( bool  take_sem)

◆ spi_detect()

uint8_t spi_detect ( )

◆ spi_spiRecv()

uint8_t spi_spiRecv ( void  )

◆ spi_spiSend()

uint8_t spi_spiSend ( uint8_t  b)

◆ spi_spiTransfer()

void spi_spiTransfer ( const uint8_t *  send,
uint32_t  send_len,
uint8_t *  recv,
uint32_t  recv_len 
)

◆ spi_spiXchg()

uint8_t spi_spiXchg ( uint8_t  b)

◆ spi_waitFor()

uint8_t spi_waitFor ( uint8_t  out,
spi_WaitFunc  cb,
uint32_t  dly 
)

◆ spi_yield()

void spi_yield ( )

Variable Documentation

◆ sd_max_sectors

uint32_t sd_max_sectors =0
static

Definition at line 80 of file sd.c.

◆ Stat

volatile DSTATUS Stat = STA_NOINIT
static

Definition at line 77 of file sd.c.

◆ Timer1

volatile uint16_t Timer1
static

Definition at line 79 of file sd.c.

◆ Timer2

volatile uint16_t Timer2
static

Definition at line 79 of file sd.c.