MW-AHRS X1 빌드 관련 오류 문의 > Module_Forum

본문 바로가기
사이트 내 전체검색

Module_Forum

MW-AHRS X1 빌드 관련 오류 문의

페이지 정보

profile_image
작성자 jujang
댓글 14건 조회 206회 작성일 25-08-26 15:56

본문

구매한 Sensor: MW-AHRS X1

사용 환경: ROS2, jetson ORIN NX

개발 언어: C++, PYTHON

MwAHRS.a(MwSerial.o): Relocations in generic ELF (EM: 62) /usr/bin/ld: /home/scout/IMU/PC_AHRS_ROS2/stella_ahrs/lib/MwAHRS.a(MwSerial.o): Relocations in generic ELF (EM: 62) /usr/bin/ld: /home/scout/IMU/PC_AHRS_ROS2/stella_ahrs/lib/MwAHRS.a: error adding symbols: file in wrong format collect2: error: ld returned 1 exit status gmake[2]: *** [CMakeFiles/stella_ahrs_node.dir/build.make:193: stella_ahrs_node] Error 1 gmake[1]: *** [CMakeFiles/Makefile2:137: CMakeFiles/stella_ahrs_node.dir/all] Error 2 gmake: *** [Makefile:146: all] Error 2 --- Failed <<< stella_ahrs [12.5s, exited with code 2]

안녕하세요 MW-AHRS X1 ros2 연동을 위해 패키지를 빌드하던 중 위와 같은 오류가 발생하여 문의 드립니다.

댓글목록

profile_image

최고관리자님의 댓글

최고관리자 작성일

안녕하세요. 아키텍처가 달라서 생기는 현상입니다.

https://github.com/ntrexlab/2th_NtrexAHRS_lib_ROS

여기서 해당되는 파일로 교체 하셔야됩니다.

profile_image

jujang님의 댓글

jujang 작성일

답변 주셔서 감사합니다. 말씀 주신대로 변경하였음에도
scout@ubuntu:~/PC_AHRS_ROS2$ colcon build
Starting >>> stella_ahrs
--- stderr: stella_ahrs                               
/home/scout/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp: In function ‘void* AHRS_thread(void*)’:
/home/scout/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp:49:1: warning: no return statement in function returning non-void [-Wreturn-type]
  49 | }
      | ^
/home/scout/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp:4:25: warning: unused parameter ‘arg’ [-Wunused-parameter]
    4 | void *AHRS_thread(void *arg)
      |                  ~~~~~~^~~
/home/scout/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp: In function ‘int main(int, char**)’:
/home/scout/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp:52:26: warning: ISO C++ forbids converting a string constant to ‘char*’ [-Wwrite-strings]
  52 |        if(MW_SerialOpen("/dev/ttyUSB0", 115200) < 0)
      |                          ^~~~~~~~~~~~~~
/usr/bin/ld: CMakeFiles/stella_ahrs_node.dir/src/listener.cpp.o: in function `AHRS_thread(void*)':
listener.cpp:(.text+0x34): undefined reference to `MW_SerialRecv(long*, int*, char*)'
/usr/bin/ld: CMakeFiles/stella_ahrs_node.dir/src/listener.cpp.o: in function `main':
listener.cpp:(.text+0x78c): undefined reference to `MW_SerialOpen(char*, int)'
/usr/bin/ld: listener.cpp:(.text+0xb58): undefined reference to `Mw_SerialClose()'
/usr/bin/ld: CMakeFiles/stella_ahrs_node.dir/src/MwAHRS.cpp.o: in function `Mw_AHRS_init(int)':
MwAHRS.cpp:(.text+0x48): undefined reference to `MW_SerialSend(long, char*)'
/usr/bin/ld: MwAHRS.cpp:(.text+0x5c): undefined reference to `MW_SerialSend(long, char*)'
/usr/bin/ld: MwAHRS.cpp:(.text+0x70): undefined reference to `MW_SerialSend(long, char*)'
collect2: error: ld returned 1 exit status
gmake[2]: *** [CMakeFiles/stella_ahrs_node.dir/build.make:193: stella_ahrs_node] Error 1
gmake[1]: *** [CMakeFiles/Makefile2:137: CMakeFiles/stella_ahrs_node.dir/all] Error 2
gmake: *** [Makefile:146: all] Error 2
---
Failed  <<< stella_ahrs [13.0s, exited with code 2]

Summary: 0 packages finished [13.6s]
  1 package failed: stella_ahrs
  1 package had stderr output: stella_ahrs
위와같은 오류가 발생하여서 다시 댓글 남깁니다.

profile_image

최고관리자님의 댓글

최고관리자 작성일

혹시 코드도 해당 깃헙에 업로드 된 걸로 받으셨는지요?

번거로우시겠지만 확인 부탁드리겠습니다.

profile_image

jujang님의 댓글

jujang 작성일

MW_AHRS_aarch64.a 이 파일로 교체 후 cmakelist또한 target_link_libraries(${PROJECT_NAME}_node ${CMAKE_CURRENT_SOURCE_DIR}/lib/MW_AHRS_aarch64.a)로 변경 하여 빌드 했을때 jujangchoi@jujangchoi-MS-7E01:~/PC_AHRS_ROS2$ colcon build
Starting >>> stella_ahrs
--- stderr: stella_ahrs                             
/home/jujangchoi/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp: In function ‘void* AHRS_thread(void*)’:
/home/jujangchoi/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp:49:1: warning: no return statement in function returning non-void [-Wreturn-type]
  49 | }
      | ^
/home/jujangchoi/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp:4:25: warning: unused parameter ‘arg’ [-Wunused-parameter]
    4 | void *AHRS_thread(void *arg)
      |                  ~~~~~~^~~
/home/jujangchoi/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp: In function ‘int main(int, char**)’:
/home/jujangchoi/PC_AHRS_ROS2/stella_ahrs/src/listener.cpp:52:26: warning: ISO C++ forbids converting a string constant to ‘char*’ [-Wwrite-strings]
  52 |        if(MW_SerialOpen("/dev/ttyUSB0", 115200) < 0)
      |                          ^~~~~~~~~~~~~~
/usr/bin/ld: CMakeFiles/stella_ahrs_node.dir/src/listener.cpp.o: in function `AHRS_thread(void*)':
listener.cpp:(.text+0x3f): undefined reference to `MW_SerialRecv(long*, int*, char*)'
/usr/bin/ld: CMakeFiles/stella_ahrs_node.dir/src/listener.cpp.o: in function `main':
listener.cpp:(.text+0x905): undefined reference to `MW_SerialOpen(char*, int)'
/usr/bin/ld: listener.cpp:(.text+0xf3e): undefined reference to `Mw_SerialClose()'
/usr/bin/ld: CMakeFiles/stella_ahrs_node.dir/src/MwAHRS.cpp.o: in function `Mw_AHRS_init(int)':
MwAHRS.cpp:(.text+0x52): undefined reference to `MW_SerialSend(long, char*)'
/usr/bin/ld: MwAHRS.cpp:(.text+0x70): undefined reference to `MW_SerialSend(long, char*)'
/usr/bin/ld: MwAHRS.cpp:(.text+0x8e): undefined reference to `MW_SerialSend(long, char*)'
collect2: error: ld returned 1 exit status
gmake[2]: *** [CMakeFiles/stella_ahrs_node.dir/build.make:193: stella_ahrs_node] Error 1
gmake[1]: *** [CMakeFiles/Makefile2:137: CMakeFiles/stella_ahrs_node.dir/all] Error 2
gmake: *** [Makefile:146: all] Error 2
---
Failed  <<< stella_ahrs [3.06s, exited with code 2]

Summary: 0 packages finished [3.18s]
  1 package failed: stella_ahrs
  1 package had stderr output: stella_ahrs
오류가 뜹니다

profile_image

최고관리자님의 댓글의 댓글

최고관리자 작성일

아래 ros2 패키지가 X1에 맞춰진 최신 패키지입니다.
https://github.com/ntrexlab/2th_NtrexAHRS_lib_ROS/tree/ver_2.0/ros2_example/stella_ahrs

이 패키지로 확인하여 주세요.

profile_image

jujang님의 댓글

jujang 작성일

위 패키지로 빌드 하여 ros2 launch stella_ahrs stella_ahrs_launch.py를 실행하니

scout@ubuntu:~/2th_NtrexAHRS_lib_ROS/ros2_example$ ros2 launch stella_ahrs stella_ahrs_launch.py
[INFO] [launch]: All log files can be found below /home/scout/.ros/log/2025-09-04-16-50-26-135283-ubuntu-102166
[INFO] [launch]: Default logging verbosity is set to INFO
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Caught multiple exceptions when trying to load file of format [py]:
 - TypeError: LifecycleNode.__init__() missing 2 required keyword-only arguments: 'name' and 'namespace'
 - InvalidFrontendLaunchFileError: The launch file may have a syntax error, or its format is unknown이 떠서 launch.py에 node_name='stella_ahrs_node', name='stella_ahrs_node', 를 추가한 후 다시 빌드하여 실행하였더니
scout@ubuntu:~/2th_NtrexAHRS_lib_ROS/ros2_example$ ros2 launch stella_ahrs stella_ahrs_launch.py
[INFO] [launch]: All log files can be found below /home/scout/.ros/log/2025-09-04-16-54-55-316236-ubuntu-103167
[INFO] [launch]: Default logging verbosity is set to INFO
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Caught multiple exceptions when trying to load file of format [py]:
 - TypeError: Node.__init__() missing 1 required keyword-only argument: 'executable'
 - InvalidFrontendLaunchFileError: The launch file may have a syntax error, or its format is unknown

이런 오류가 발생합니다

profile_image

jujang님의 댓글

jujang 작성일

그리구 원래 launch.py에 'name' and 'namespace' 이거 있던데 왜 처음에 저 오류가 뜰가요?

profile_image

최고관리자님의 댓글의 댓글

최고관리자 작성일

해당 패키지는 ros2 foxy를 기준으로 개발되었습니다.
아마 사용하시는 ros2 버전이 humble 혹은 jazzy이신 걸로 예상됩니다.

ros2 humble 부터 LifecycleNode의 설정 인자를 작성하는 방법이 일부 변경되어 발생하는 에러입니다.

    driver_node = LifecycleNode(package='stella_ahrs',
                                node_executable='stella_ahrs_node',
                                node_name='stella_ahrs_node',
                                output='screen',
                                emulate_tty=True,
                                node_namespace='/',
                                )

위 부분에서 아래처럼 node_를 제거하시면 해당 에러가 발생하지 않습니다.

    driver_node = LifecycleNode(package='stella_ahrs',
                                executable='stella_ahrs_node',
                                name='stella_ahrs_node',
                                output='screen',
                                emulate_tty=True,
                                namespace='/',
                                )

profile_image

jujang님의 댓글

jujang 작성일

수정 후 launch단계에서 scout@ubuntu:~/2th_NtrexAHRS_lib_ROS/ros2_example$ ros2 launch stella_ahrs stella_ahrs_launch.py
[INFO] [launch]: All log files can be found below /home/scout/.ros/log/2025-09-04-17-12-15-675829-ubuntu-117130
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [stella_ahrs_node-1]: process started with pid [117141]
[stella_ahrs_node-1] [INFO] [1756973541.162734274] [stella_ahrs_node]: product_id  : 5011
[stella_ahrs_node-1]
[stella_ahrs_node-1] [INFO] [1756973541.163108751] [stella_ahrs_node]: software_ver : 500
[stella_ahrs_node-1]
[stella_ahrs_node-1] [INFO] [1756973541.163154352] [stella_ahrs_node]: hardware_ver : 400
[stella_ahrs_node-1]
[stella_ahrs_node-1] [INFO] [1756973541.163178673] [stella_ahrs_node]: function_ver : 15
[stella_ahrs_node-1]
[stella_ahrs_node-1] Set Error : [33], [18] index mismatch
[stella_ahrs_node-1] Set Error : [34], [19] index mismatch
[stella_ahrs_node-1] Set Error : [35], [15] index mismatch
[stella_ahrs_node-1] Set Error : [36], [07] index mismatch
[stella_ahrs_node-1] [INFO] [1756973545.255926519] [stella_ahrs_node]: MW-AHRS ROS Init Fail

이런 오류가 발생합니다.
ttyUSB는 제대로 맞춰 놓은 상태입니다

profile_image

최고관리자님의 댓글의 댓글

최고관리자 작성일

아래 공지사항에서 pdf 문서를 확인하여 보시면 유사한 문제가 발생하였을 때 해결했던 방법이 있습니다.
https://idea.synology.me/bbs/board.php?bo_table=forum&wr_id=38

해당 문서의 내용을 적용하였을 때 동일한 문제가 발생하는지 확인하여 주세요.

profile_image

jujang님의 댓글

jujang 작성일

scout@ubuntu:~/2th_NtrexAHRS_lib_ROS/ros2_example$ ros2 launch stella_ahrs stella_ahrs_launch.py
[INFO] [launch]: All log files can be found below /home/scout/.ros/log/2025-09-04-17-45-07-457232-ubuntu-125066
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [stella_ahrs_node-1]: process started with pid [125077]

이 상태에서 오류는 뜨지 않지만
scout@ubuntu:~$ ros2 topic list
/diagnostics
/parameter_events
/rosout
/stella_ahrs_node/transition_event
/velodyne_packets
/velodyne_points
토픽에 imu가 뜨지 않습니다.

profile_image

최고관리자님의 댓글의 댓글

최고관리자 작성일

토픽이 안 나오는 현상과 토픽 publish 전 나와야 하는 로그가 일부 보이지 않는 것으로 확인됩니다.

혹시 수정하신 mw_ahrs.cpp 파일의 코드를 올려주실 수 있으실까요?

profile_image

jujang님의 댓글

jujang 작성일

#include "mw_ahrs.hpp"
#include "mw_ahrsX1_def.hpp"

static bool AHRS = false;

namespace ntrex
{
  void MwAhrsRosDriver::StartReading()
  {
    AHRS = true;
    sleep(1);
    reading_thread_ = std::thread(&MwAhrsRosDriver::MwAhrsRead, this);
  }

  void MwAhrsRosDriver::StopReading()
  {
    if (AHRS)
    {
      AHRS = false;
      sleep(1);
      if (reading_thread_.joinable())
      {
        reading_thread_.join();
      }
    }
  }

  void MwAhrsRosDriver::StartPubing()
  {
    if (AHRS)
      publisher_thread_ = std::thread(&MwAhrsRosDriver::publish_topic, this);
  }

  void MwAhrsRosDriver::StopPubing()
  {
    if (publisher_thread_.joinable())
      publisher_thread_.join();
  }

  void MwAhrsRosDriver::MW_AHRS_Covariance(void)
  {
    imu_data_raw_msg = sensor_msgs::msg::Imu();
    imu_data_msg = sensor_msgs::msg::Imu();
    imu_magnetic_msg = sensor_msgs::msg::MagneticField();
    imu_yaw_msg = std_msgs::msg::Float64();

    linear_acceleration_cov = linear_acceleration_stddev_ * linear_acceleration_stddev_;
    angular_velocity_cov = angular_velocity_stddev_ * angular_velocity_stddev_;
    magnetic_field_cov = magnetic_field_stddev_ * magnetic_field_stddev_;
    orientation_cov = orientation_stddev_ * orientation_stddev_;

    imu_data_raw_msg.linear_acceleration_covariance[0] =
        imu_data_raw_msg.linear_acceleration_covariance[4] =
            imu_data_raw_msg.linear_acceleration_covariance[8] =
                imu_data_msg.linear_acceleration_covariance[0] =
                    imu_data_msg.linear_acceleration_covariance[4] =
                        imu_data_msg.linear_acceleration_covariance[8] =
                            linear_acceleration_cov;

    imu_data_raw_msg.angular_velocity_covariance[0] =
        imu_data_raw_msg.angular_velocity_covariance[4] =
            imu_data_raw_msg.angular_velocity_covariance[8] =
                imu_data_msg.angular_velocity_covariance[0] =
                    imu_data_msg.angular_velocity_covariance[4] =
                        imu_data_msg.angular_velocity_covariance[8] =
                            angular_velocity_cov;

    imu_data_msg.orientation_covariance[0] =
        imu_data_msg.orientation_covariance[4] =
            imu_data_msg.orientation_covariance[8] =
                orientation_cov;

    imu_magnetic_msg.magnetic_field_covariance[0] =
        imu_magnetic_msg.magnetic_field_covariance[4] =
            imu_magnetic_msg.magnetic_field_covariance[8] =
                magnetic_field_cov;
  }

  void MwAhrsRosDriver::MwAhrsRead()
  {
    while (AHRS)
    {
      unsigned char data[8];

      if (MW_AHRS_Read(data))
      {
        switch ((int)(unsigned char)data[1])
        {
        case ACC:
          acc_value[0] = (int16_t)(((int)(unsigned char)data[2] | (int)(unsigned char)data[3] << 8)) / 1000.0;
          acc_value[1] = (int16_t)(((int)(unsigned char)data[4] | (int)(unsigned char)data[5] << 8)) / 1000.0;
          acc_value[2] = (int16_t)(((int)(unsigned char)data[6] | (int)(unsigned char)data[7] << 8)) / 1000.0;

          imu_data_raw_msg.linear_acceleration.x = imu_data_msg.linear_acceleration.x =
              acc_value[0] * convertor_g2a;
          imu_data_raw_msg.linear_acceleration.y = imu_data_msg.linear_acceleration.y =
              acc_value[1] * convertor_g2a;
          imu_data_raw_msg.linear_acceleration.z = imu_data_msg.linear_acceleration.z =
              acc_value[2] * convertor_g2a;

          break;

        case GYO:
          gyr_value[0] = (int16_t)(((int)(unsigned char)data[2] | (int)(unsigned char)data[3] << 8)) / 10.0;
          gyr_value[1] = (int16_t)(((int)(unsigned char)data[4] | (int)(unsigned char)data[5] << 8)) / 10.0;
          gyr_value[2] = (int16_t)(((int)(unsigned char)data[6] | (int)(unsigned char)data[7] << 8)) / 10.0;

          imu_data_raw_msg.angular_velocity.x = imu_data_msg.angular_velocity.x =
              gyr_value[0] * convertor_d2r;
          imu_data_raw_msg.angular_velocity.y = imu_data_msg.angular_velocity.y =
              gyr_value[1] * convertor_d2r;
          imu_data_raw_msg.angular_velocity.z = imu_data_msg.angular_velocity.z =
              gyr_value[2] * convertor_d2r;

          break;

        case DEG:
          deg_value[0] = (int16_t)(((int)(unsigned char)data[2] | (int)(unsigned char)data[3] << 8)) / 100.0;
          deg_value[1] = (int16_t)(((int)(unsigned char)data[4] | (int)(unsigned char)data[5] << 8)) / 100.0;
          deg_value[2] = (int16_t)(((int)(unsigned char)data[6] | (int)(unsigned char)data[7] << 8)) / 100.0;

          roll = deg_value[0] * convertor_d2r;
          pitch = deg_value[1] * convertor_d2r;
          yaw = deg_value[2] * convertor_d2r;

          tf_orientation = Euler2Quaternion(roll, pitch, yaw);

          imu_yaw_msg.data = deg_value[2];

          imu_data_msg.orientation.x = tf_orientation.x();
          imu_data_msg.orientation.y = tf_orientation.y();
          imu_data_msg.orientation.z = tf_orientation.z();
          imu_data_msg.orientation.w = tf_orientation.w();

          break;

        case MAG:
          mag_value[0] = (int16_t)(((int)(unsigned char)data[2] | (int)(unsigned char)data[3] << 8)) / 10.0;
          mag_value[1] = (int16_t)(((int)(unsigned char)data[4] | (int)(unsigned char)data[5] << 8)) / 10.0;
          mag_value[2] = (int16_t)(((int)(unsigned char)data[6] | (int)(unsigned char)data[7] << 8)) / 10.0;

          imu_magnetic_msg.magnetic_field.x = mag_value[0] / convertor_ut2t;
          imu_magnetic_msg.magnetic_field.y = mag_value[1] / convertor_ut2t;
          imu_magnetic_msg.magnetic_field.z = mag_value[2] / convertor_ut2t;

          break;
        }
      }
    }
  }

  void MwAhrsRosDriver::publish_topic()
  {
    rclcpp::Rate rate(1000);

    while (rclcpp::ok() && AHRS)
    {
      rclcpp::Time now = this->get_clock()->now();

      imu_data_raw_msg.header.stamp = imu_data_msg.header.stamp = imu_magnetic_msg.header.stamp = now;
      imu_data_raw_msg.header.frame_id = imu_data_msg.header.frame_id = imu_magnetic_msg.header.frame_id = frame_id_;

      imu_data_raw_pub_->publish(std::move(imu_data_raw_msg));
      imu_data_pub_->publish(std::move(imu_data_msg));
      imu_mag_pub_->publish(std::move(imu_magnetic_msg));
      imu_yaw_pub_->publish(std::move(imu_yaw_msg));

      if (publish_tf_)
      {
        geometry_msgs::msg::TransformStamped tf;
        tf.header.stamp = now;
        tf.header.frame_id = parent_frame_id_;
        tf.child_frame_id = frame_id_;
        tf.transform.translation.x = 0.0;
        tf.transform.translation.y = 0.0;
        tf.transform.translation.z = 0.0;
        tf.transform.rotation = imu_data_msg.orientation;

        broadcaster_->sendTransform(tf);
      }
      rate.sleep();
    }
  }

  tf2::Quaternion MwAhrsRosDriver::Euler2Quaternion(float roll, float pitch, float yaw)
  {
    float qx = (sin(roll / 2) * cos(pitch / 2) * cos(yaw / 2)) -
              (cos(roll / 2) * sin(pitch / 2) * sin(yaw / 2));
    float qy = (cos(roll / 2) * sin(pitch / 2) * cos(yaw / 2)) +
              (sin(roll / 2) * cos(pitch / 2) * sin(yaw / 2));
    float qz = (cos(roll / 2) * cos(pitch / 2) * sin(yaw / 2)) -
              (sin(roll / 2) * sin(pitch / 2) * cos(yaw / 2));
    float qw = (cos(roll / 2) * cos(pitch / 2) * cos(yaw / 2)) +
              (sin(roll / 2) * sin(pitch / 2) * sin(yaw / 2));

    tf2::Quaternion q(qx, qy, qz, qw);
    return q;
  }

  bool MwAhrsRosDriver::MW_AHRS_Setting()
  {
    bool res = true;

    long product_id = 0, software_ver = 0, hardware_ver = 0, function_ver = 0;

    long sync_port = CI_USB, sync_period = 10, sync_trmode = CI_Binary, sync_data = 15, FlashWrite = 1;

    res &= MW_AHRS_GetValI(product_id,  CI_PRODUCT_ID);
    res &= MW_AHRS_GetValI(software_ver, CI_SW_VERSION);
    res &= MW_AHRS_GetValI(hardware_ver, CI_HW_VERSION);
    res &= MW_AHRS_GetValI(function_ver, CI_FN_VERSION);

    RCLCPP_INFO(this->get_logger(), "product_id  : %ld \n", product_id);
    RCLCPP_INFO(this->get_logger(), "software_ver : %ld \n", software_ver);
    RCLCPP_INFO(this->get_logger(), "hardware_ver : %ld \n", hardware_ver);
    RCLCPP_INFO(this->get_logger(), "function_ver : %ld \n", function_ver);

    res &= MW_AHRS_SetValI(sync_port,  CI_SYNC_PORT);
    res &= MW_AHRS_SetValI(sync_period, CI_SYNC_PERIOD);
    res &= MW_AHRS_SetValI(sync_trmode, CI_SYNC_TRMODE);
    res &= MW_AHRS_SetValI(sync_data,  CI_SYNC_DATA);
    //res &= MW_AHRS_SetValI(FlashWrite,  CI_SYS_COMMAND);

    //res &= MW_AHRS_NvicReset ();

    return res;
  }

  MwAhrsRosDriver::MwAhrsRosDriver(char *port, int baud_rate) : Node("MW_AHRS_ROS2")
  {
    bool res = false;

    res = MW_AHRS_Connect(port, baud_rate);

    if(res) res = MW_AHRS_Setting();

    if (res)
    {
      this->declare_parameter("linear_acceleration_stddev", 0.0);
      this->declare_parameter("angular_velocity_stddev", 0.0);
      this->declare_parameter("magnetic_field_stddev", 0.0);
      this->declare_parameter("orientation_stddev", 0.0);

      this->get_parameter("linear_acceleration_stddev", linear_acceleration_stddev_);
      this->get_parameter("angular_velocity_stddev", angular_velocity_stddev_);
      this->get_parameter("magnetic_field_stddev", magnetic_field_stddev_);
      this->get_parameter("orientation_stddev", orientation_stddev_);

      MW_AHRS_Covariance();

      StartReading();

      auto qos = rclcpp::QoS(rclcpp::KeepLast(10)) .reliable() .durability_volatile();

      imu_data_raw_pub_ = this->create_publisher<sensor_msgs::msg::Imu>("imu/data_raw", qos);
      imu_data_pub_ = this->create_publisher<sensor_msgs::msg::Imu>("imu/data", qos);
      imu_mag_pub_ = this->create_publisher<sensor_msgs::msg::MagneticField>("imu/mag", qos);
      imu_yaw_pub_ = this->create_publisher<std_msgs::msg::Float64>("imu/yaw", qos);

      StartPubing();
      RCLCPP_INFO(this->get_logger(), "MW-AHRS ROS Init Success");
    }
    else
    {
      RCLCPP_INFO(this->get_logger(), "MW-AHRS ROS Init

profile_image

최고관리자님의 댓글

최고관리자 작성일

확인이 늦어서 죄송합니다.

혹시 수정 하신 부분이 어디이실까요?

/stella_ahrs_node/transition_event 해당 토픽이 보여서 말씀드렸습니다.

회원로그인

회원가입