Browse Source

增加测试打印消息

my1.12
那个Zeng 3 years ago
parent
commit
c0cc1ba6d0
  1. 10
      platforms/common/i2c_spi_buses.cpp
  2. 2
      platforms/common/include/px4_platform_common/i2c_spi_buses.h
  3. 1
      platforms/common/px4_work_queue/WorkQueueManager.cpp
  4. 5
      src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp
  5. 12
      src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c_main.cpp
  6. 6
      src/drivers/magnetometer/hmc5883/hmc5883_i2c.cpp
  7. 3
      src/drivers/magnetometer/hmc5883/hmc5883_main.cpp

10
platforms/common/i2c_spi_buses.cpp

@ -461,6 +461,8 @@ struct I2CSPIDriverInitializing {
static void initializer_trampoline(void *argument) static void initializer_trampoline(void *argument)
{ {
I2CSPIDriverInitializing *data = (I2CSPIDriverInitializing *)argument; I2CSPIDriverInitializing *data = (I2CSPIDriverInitializing *)argument;
printf("IN{%d} instance: %d\n",__LINE__,data->runtime_instance);
data->instance = data->instantiate(data->cli, data->iterator, data->runtime_instance); data->instance = data->instantiate(data->cli, data->iterator, data->runtime_instance);
} }
@ -476,6 +478,7 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
bool started = false; bool started = false;
while (iterator.next()) { while (iterator.next()) {
printf("MS{%d} bus: %i\n",__LINE__, iterator.bus());
if (iterator.instance()) { if (iterator.instance()) {
PX4_WARN("Already running on bus %i", iterator.bus()); PX4_WARN("Already running on bus %i", iterator.bus());
continue; continue;
@ -485,6 +488,7 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
device::Device::DeviceId device_id{}; device::Device::DeviceId device_id{};
device_id.devid_s.bus = iterator.bus(); device_id.devid_s.bus = iterator.bus();
printf("MS{%d} busType: %d\n",__LINE__,iterator.busType());
switch (iterator.busType()) { switch (iterator.busType()) {
case BOARD_I2C_BUS: device_id.devid_s.bus_type = device::Device::DeviceBusType_I2C; break; case BOARD_I2C_BUS: device_id.devid_s.bus_type = device::Device::DeviceBusType_I2C; break;
@ -501,23 +505,29 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
initializer.wait(); initializer.wait();
I2CSPIDriverBase *instance = initializer_data.instance; I2CSPIDriverBase *instance = initializer_data.instance;
// printf("MS{%d} instance: %d\n",__LINE__,(int)instance);
if (!instance) { if (!instance) {
PX4_DEBUG("instantiate failed (no device on bus %i (devid 0x%x)?)", iterator.bus(), iterator.devid()); PX4_DEBUG("instantiate failed (no device on bus %i (devid 0x%x)?)", iterator.bus(), iterator.devid());
printf("{%d}instantiate failed (no device on bus %i (devid 0x%02x)?)\n",__LINE__, iterator.bus(), device_id.devid);
continue; continue;
} }
printf("{%d}instantiate ok on bus %i (devid 0x%02x) \n",__LINE__, iterator.bus(), device_id.devid);
if (cli.i2c_address != 0 && instance->_i2c_address == 0) { if (cli.i2c_address != 0 && instance->_i2c_address == 0) {
PX4_ERR("Bug: driver %s does not pass the I2C address to I2CSPIDriverBase", instance->ItemName()); PX4_ERR("Bug: driver %s does not pass the I2C address to I2CSPIDriverBase", instance->ItemName());
printf("{%d}Bug: driver %s does not pass the I2C address to I2CSPIDriverBase\n",__LINE__, instance->ItemName());
} }
iterator.addInstance(instance); iterator.addInstance(instance);
started = true; started = true;
printf("MS{%d} busType: %d\n",__LINE__,(int)iterator.busType());
// print some info that we are running // print some info that we are running
switch (iterator.busType()) { switch (iterator.busType()) {
case BOARD_I2C_BUS: case BOARD_I2C_BUS:
PX4_INFO_RAW("%s #%i on I2C bus %d", instance->ItemName(), runtime_instance, iterator.bus()); PX4_INFO_RAW("%s #%i on I2C bus %d", instance->ItemName(), runtime_instance, iterator.bus());
printf("MS{%d} addr: %02x, rot:%d\n",__LINE__,cli.i2c_address,cli.rotation);
if (iterator.external()) { if (iterator.external()) {
PX4_INFO_RAW(" (external)"); PX4_INFO_RAW(" (external)");
} }

2
platforms/common/include/px4_platform_common/i2c_spi_buses.h

@ -87,6 +87,7 @@ public:
/** /**
* Parse CLI arguments (for drivers that don't need any custom arguments, otherwise getopt() should be used) * Parse CLI arguments (for drivers that don't need any custom arguments, otherwise getopt() should be used)
* CLI 使 getopt()
* @return command (e.g. "start") or nullptr on error or unknown argument * @return command (e.g. "start") or nullptr on error or unknown argument
*/ */
const char *parseDefaultArguments(int argc, char *argv[]); const char *parseDefaultArguments(int argc, char *argv[]);
@ -139,6 +140,7 @@ private:
/** /**
* @class BusInstanceIterator * @class BusInstanceIterator
* Iterate over running instances and/or configured I2C/SPI buses with given filter options. * Iterate over running instances and/or configured I2C/SPI buses with given filter options.
* 使 / I2C/SPI 线
*/ */
class BusInstanceIterator class BusInstanceIterator
{ {

1
platforms/common/px4_work_queue/WorkQueueManager.cpp

@ -127,6 +127,7 @@ device_bus_to_wq(uint32_t device_id_int)
const device::Device::DeviceBusType bus_type = device_id.devid_s.bus_type; const device::Device::DeviceBusType bus_type = device_id.devid_s.bus_type;
const uint8_t bus = device_id.devid_s.bus; const uint8_t bus = device_id.devid_s.bus;
printf("WQ{%d}id:%d type: %d,bus:%d\n",__LINE__,device_id_int,(int)bus_type,bus);
if (bus_type == device::Device::DeviceBusType_I2C) { if (bus_type == device::Device::DeviceBusType_I2C) {
switch (bus) { switch (bus) {
case 0: return wq_configurations::I2C0; case 0: return wq_configurations::I2C0;

5
src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp

@ -40,6 +40,8 @@
*/ */
#include "tfmini_i2c.h" #include "tfmini_i2c.h"
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0])) #define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0]))
@ -69,6 +71,7 @@ TFmini_i2c::~TFmini_i2c()
int int
TFmini_i2c::init() TFmini_i2c::init()
{ {
printf("TFmini_i2c: init() \n");
// Perform I2C init (and probe) first. // Perform I2C init (and probe) first.
if (I2C::init() != PX4_OK) { if (I2C::init() != PX4_OK) {
return PX4_ERROR; return PX4_ERROR;
@ -157,6 +160,8 @@ TFmini_i2c::check_checksum(uint8_t *arr, int pkt_len)
int int
TFmini_i2c::probe() TFmini_i2c::probe()
{ {
printf("TFmini_i2c: probe() \n");
const uint8_t CMD_FW_VERSION[] = { 0x5A, 0x04, 0x01, 0x5F }; const uint8_t CMD_FW_VERSION[] = { 0x5A, 0x04, 0x01, 0x5F };
const uint8_t CMD_SYSTEM_RESET[] = { 0x5A, 0x04, 0x04, 0x62 }; const uint8_t CMD_SYSTEM_RESET[] = { 0x5A, 0x04, 0x04, 0x62 };
const uint8_t CMD_OUTPUT_FORMAT_CM[] = { 0x5A, 0x05, 0x05, 0x01, 0x65 }; const uint8_t CMD_OUTPUT_FORMAT_CM[] = { 0x5A, 0x05, 0x05, 0x01, 0x65 };

12
src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c_main.cpp

@ -64,7 +64,7 @@ Setup/usage information: https://docs.px4.io/master/en/sensor/lidar_lite.html
PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor");
PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
PRINT_MODULE_USAGE_PARAM_INT('R', 25, 0, 25, "Sensor rotation - downward facing by default", true); PRINT_MODULE_USAGE_PARAM_INT('R', 25, 0, 25, "Sensor rotation - forward facing by default", true);
PRINT_MODULE_USAGE_COMMAND("regdump"); PRINT_MODULE_USAGE_COMMAND("regdump");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
} }
@ -72,8 +72,9 @@ Setup/usage information: https://docs.px4.io/master/en/sensor/lidar_lite.html
I2CSPIDriverBase *TFmini_i2c::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator, I2CSPIDriverBase *TFmini_i2c::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance) int runtime_instance)
{ {
// 类实例,传入BusInstanceIterator总线实例迭代器参数,解析 CLI 参数
printf("instantiate: bus:%d,ori:%d,freq:%d \n", iterator.bus(), cli.orientation, cli.bus_frequency);
TFmini_i2c* instance = new TFmini_i2c(iterator.configuredBusOption(), iterator.bus(), cli.orientation, cli.bus_frequency); TFmini_i2c* instance = new TFmini_i2c(iterator.configuredBusOption(), iterator.bus(), cli.orientation, cli.bus_frequency);
if (instance == nullptr) { if (instance == nullptr) {
PX4_ERR("alloc failed"); PX4_ERR("alloc failed");
return nullptr; return nullptr;
@ -99,8 +100,8 @@ extern "C" __EXPORT int tfmini_i2c_main(int argc, char *argv[])
int ch; int ch;
using ThisDriver = TFmini_i2c; using ThisDriver = TFmini_i2c;
BusCLIArguments cli{true, false}; BusCLIArguments cli{true, false};
cli.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING; cli.orientation = distance_sensor_s::ROTATION_FORWARD_FACING;
cli.default_i2c_frequency = 100000; cli.default_i2c_frequency = 400000;
while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) {
switch (ch) { switch (ch) {
@ -117,9 +118,10 @@ extern "C" __EXPORT int tfmini_i2c_main(int argc, char *argv[])
return -1; return -1;
} }
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_DIST_DEVTYPE_LL40LS); BusInstanceIterator iterator(MODULE_NAME, cli, DRV_DIST_DEVTYPE_TFMINI_I2C);
if (!strcmp(verb, "start")) { if (!strcmp(verb, "start")) {
printf("%s,cli: drv:%d,ori:%d,freq:%d \n",__FILE__, DRV_DIST_DEVTYPE_TFMINI_I2C, cli.orientation, cli.default_i2c_frequency);
return ThisDriver::module_start(cli, iterator); return ThisDriver::module_start(cli, iterator);
} }

6
src/drivers/magnetometer/hmc5883/hmc5883_i2c.cpp

@ -39,10 +39,13 @@
#include <px4_platform_common/px4_config.h> #include <px4_platform_common/px4_config.h>
#include <drivers/device/i2c.h> #include <drivers/device/i2c.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#include "hmc5883.h" #include "hmc5883.h"
#define HMC5883L_ADDRESS 0x1E #define HMC5883L_ADDRESS 0x1E
// #define HMC5883L_ADDRESS 0x11
device::Device *HMC5883_I2C_interface(int bus, int bus_frequency); device::Device *HMC5883_I2C_interface(int bus, int bus_frequency);
@ -72,6 +75,7 @@ HMC5883_I2C::HMC5883_I2C(int bus, int bus_frequency) :
int HMC5883_I2C::probe() int HMC5883_I2C::probe()
{ {
printf("HMC5883_I2C: probe() \n");
uint8_t data[3] = {0, 0, 0}; uint8_t data[3] = {0, 0, 0};
_retries = 10; _retries = 10;
@ -85,6 +89,8 @@ int HMC5883_I2C::probe()
_retries = 2; _retries = 2;
printf("HMC5883 {%d} probe:%d,ori:%d,freq:%d \n",__LINE__, data[0],data[1],data[2]);
DEVICE_DEBUG("ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
if ((data[0] != ID_A_WHO_AM_I) || if ((data[0] != ID_A_WHO_AM_I) ||
(data[1] != ID_B_WHO_AM_I) || (data[1] != ID_B_WHO_AM_I) ||
(data[2] != ID_C_WHO_AM_I)) { (data[2] != ID_C_WHO_AM_I)) {

3
src/drivers/magnetometer/hmc5883/hmc5883_main.cpp

@ -49,8 +49,10 @@ I2CSPIDriverBase *HMC5883::instantiate(const BusCLIArguments &cli, const BusInst
int runtime_instance) int runtime_instance)
{ {
device::Device *interface = nullptr; device::Device *interface = nullptr;
printf("HMC5883: bus:%d,ori:%d,freq:%d \n", iterator.bus(), cli.orientation, cli.bus_frequency);
if (iterator.busType() == BOARD_I2C_BUS) { if (iterator.busType() == BOARD_I2C_BUS) {
printf("HMC5883 {%d} bus:%d,ori:%d,freq:%d \n",__LINE__, iterator.bus(), cli.orientation, cli.bus_frequency);
interface = HMC5883_I2C_interface(iterator.bus(), cli.bus_frequency); interface = HMC5883_I2C_interface(iterator.bus(), cli.bus_frequency);
} else if (iterator.busType() == BOARD_SPI_BUS) { } else if (iterator.busType() == BOARD_SPI_BUS) {
@ -130,6 +132,7 @@ extern "C" int hmc5883_main(int argc, char *argv[])
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_HMC5883); BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_HMC5883);
if (!strcmp(verb, "start")) { if (!strcmp(verb, "start")) {
printf("%s,cli: drv:%d,ori:%d,freq:%d \n",__FILE__, DRV_MAG_DEVTYPE_HMC5883, cli.orientation, cli.default_i2c_frequency);
return ThisDriver::module_start(cli, iterator); return ThisDriver::module_start(cli, iterator);
} }

Loading…
Cancel
Save