- SDAとSCLをSTM32ボードのi2c SDA SDLピンと接続する。
- 3.3Vを3.3に、グランドをSTM32ボードのグランドに接続する。
- VCCとVCCIOは今のところ未接続のままである。
- BMX055センサーのjp7をショート(ハンダ付け)する。
ソースファイルをダウンロードし、メインの F446RE project
の適切なフォルダにインクルードする。
BMX055.c
をダウンロードし、F446REプロジェクトのCore/Src
フォルダにインクルードする。BMX055_CONFIG.c
をダウンロードし、F446REプロジェクトのCore/Src
フォルダにインクルードする。BMX055.h
をダウンロードし、F446REプロジェクトフォルダ内のCore/Inc
フォルダにインクルードする。
StartTask02()
ループ内に、BMX055初期化用の以下のコードを追加する。。
float deltaTime = 0.015; //for now please use this value
void StartTask02(void *argument)
{
/* USER CODE BEGIN StartTask02 */
/* Infinite loop */
for(;;)
{
BMX055_init(&hi2c1, &BMX055_2, DELTATIME); // put this inside the loop
osDelay(1);
}
/* USER CODE END StartTask02 */
}
BMX055パブリッシャー関数を main.c
内で定義する。
// inside main.c
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
// other include ...
#include <std_msgs/msg/int32_multi_array.h>
#include <std_msgs/msg/float32_multi_array.h>
#include <std_msgs/msg/int32.h>
#include <std_msgs/msg/float32.h>
#include "rosidl_runtime_c/string_functions.h"
#include "BMX055.h"
/* USER CODE END Includes */
/* USER CODE BEGIN PM */
// other micro_ros related publisher var ...
rcl_publisher_t pub_bmx055_error, pub_bmx055_data,
publisher_int, pub_bmx055_raw, pub_bmx055_imu, pub_bmx055_mag;
std_msgs__msg__Int32 pub_int_msg;
std_msgs__msg__Float32MultiArray pub_arr_msg, pub_arr_msg2;
std_msgs__msg__String pub_str_msg;
sensor_msgs__msg__Imu imu_msg;
sensor_msgs__msg__MagneticField mag_msg;
/* USER CODE END PM */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
// other declared function or variable ...
uint64_t Millis(int mode) {
if (mode == 0)
return (uint64_t)HAL_GetTick() * 1000000; //nanoseconds
else if (mode == 1)
return HAL_GetTick() / 1000; //seconds
else
HAL_GetTick();
}
void Publish_Bmx055(){
// BMX055 ERROR DATA
pub_arr_msg.data.size = 19;
pub_arr_msg.data.data = BMX055_ERROR;
rcl_publish(&pub_bmx055_error, &pub_arr_msg, NULL);
// BMX055 PROCESS DATA
pub_arr_msg.data.size = BMX055_PSIZE;
pub_arr_msg.data.data = BMX055_DATA;
rcl_publish(&pub_bmx055_data, &pub_arr_msg, NULL);
// BMX055 RAW DATA
pub_arr_msg.data.size = 9;
pub_arr_msg.data.data = BMX055_RAW;
rcl_publish(&pub_bmx055_raw, &pub_arr_msg, NULL);
if (getBMX055Count() >= 200){
// IMU
imu_msg.header.frame_id = micro_ros_string_utilities_set(imu_msg.header.frame_id, "imu");
mag_msg.header.frame_id = micro_ros_string_utilities_set(mag_msg.header.frame_id, "imu");
imu_msg.header.stamp.nanosec = Millis(0);
imu_msg.header.stamp.sec = Millis(1);
mag_msg.header.stamp.nanosec = Millis(0);
mag_msg.header.stamp.sec = Millis(1);
imu_msg.linear_acceleration.x = ACCEL.x;
imu_msg.linear_acceleration.y = ACCEL.y;
imu_msg.linear_acceleration.z = ACCEL.z;
imu_msg.angular_velocity.x = GYRO_MOVEMENT.x;
imu_msg.angular_velocity.y = GYRO_MOVEMENT.y;
imu_msg.angular_velocity.z = GYRO_MOVEMENT.z;
// rotation yaw (w and z)
// rotation pitch (w and x)
// rotation roll (w and y)
imu_msg.orientation.w = QUAT.q0;
imu_msg.orientation.x = QUAT.q1;//QUAT.q1;//ORIENTATION.x;
imu_msg.orientation.y = QUAT.q2;//QUAT.q2;//ORIENTATION.y;
imu_msg.orientation.z = QUAT.q3;//QUAT.q3;//ORIENTATION.z;
mag_msg.magnetic_field.x = MAG_MOVEMENT.x;
mag_msg.magnetic_field.y = MAG_MOVEMENT.y;
mag_msg.magnetic_field.z = MAG_MOVEMENT.z;
rcl_publish(&pub_bmx055_imu, &imu_msg, NULL);
rcl_publish(&pub_bmx055_mag, &mag_msg, NULL);
}
}
/* USER CODE END 0 */
StartDefaultTask()
関数内で、BMX055パブリッシャーを作成する。
// inside StartDefaultTask()
// create publisher
RCCHECK(rclc_publisher_init_best_effort(
&pub_bmx055_error,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32MultiArray),
"/BMX055_ERROR"));
RCCHECK(rclc_publisher_init_best_effort(
&pub_bmx055_data,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32MultiArray),
"/BMX055_DATA"));
RCCHECK(rclc_publisher_init_best_effort(
&pub_bmx055_raw,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32MultiArray),
"/BMX055_RAW"));
RCCHECK(rclc_publisher_init_best_effort(
&pub_bmx055_imu,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, Imu),
"/imu/data_raw"));
RCCHECK(rclc_publisher_init_best_effort(
&pub_bmx055_mag,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, MagneticField),
"/imu/mag"));
.iocファイル
でI2C接続設定
(デフォルトはクロック速度100kHz)を設定する。
For the bmx055.py
file, set it up inside the Python ROS package. In setup.py
, include the entry point for the bmx055 script.
setup(
...
entry_points={
'console_scripts': [
...
'bmx055=lec_1.bmx055:main',
],
},
)
Use colcon build
to build the Python ROS package.
Run the Python file with ROS:
ros2 run your_python_package_name bmx055
python_パッケージ_名
のようなプレースホルダーは、プロジェクト固有の実際の情報に置き換えてください。
typedef struct POS
:
struct contains float x
, float y
and float z
POS GYRO_RAW
:
Contains XYZ raw value data of gyroscope
POS ACCEL_RAW
:
Contains XYZ raw value data of accelerator
POS MAG_RAW
:
Contains XYZ raw value data of magnetometer
float MAGDEGREE
:
Contain converted magnetometer raw value data to degree value from range 0 to 350 step by 10
float BMX055_data[BMX055_SIZE]
:
Contains processed data of sensor saved in array
[0] = Magnetometer degree value
float BMX055_raw[9]
:
Contains raw data of sensor
[0-2] = XYZ GYROSCOPE
[3-5] = XYZ ACCELERATOR
[6-8] = XYZ MAGNETOMETER
int getBMX055Count();
:
センサーのデータを正常に読み取るごとにカウンターの値を取得する
void BMX055_init(I2C_HandleTypeDef *hi2c, float timer)
:
BMX055内部の3つのセンサーすべてを初期化する
POS ORIENTATION
:
この構造体には、クォータニオン値から変換された x y z のオイラー値が格納される(度の値°)
-
ORIENTATION.x
euler x orientation (Roll) -
ORIENTATION.y
euler y orientation (Pitch) -
ORIENTATION.z
euler z orientation (Yaw)
- BMX055 DATASHEET https://www.mouser.com/datasheet/2/783/BST_BMX055_DS000-1509552.pdf