Skip to content

Conversation

tokirobot
Copy link

add openarm-diagnosis cpp script

Copy link

Congratulations! One of the builds has completed. 🍾

You can install the built RPMs by following these steps:

  • sudo yum install -y dnf-plugins-core on RHEL 8
  • sudo dnf install -y dnf-plugins-core on Fedora
  • dnf copr enable packit/enactic-openarm_can-46
  • And now you can install the packages.

Please note that the RPMs should be used only in a testing environment.

@tokirobot tokirobot closed this Oct 8, 2025
@tokirobot tokirobot reopened this Oct 8, 2025
Copy link
Contributor

@kou kou left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

+1

return false; // fall back
}
struct ifreq ifr{};
std::strncpy(ifr.ifr_name, ifname, IFNAMSIZ - 1);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We need to set \0 explicitly for a case that ifname is longer than IFNAMSIZ.

Suggested change
std::strncpy(ifr.ifr_name, ifname, IFNAMSIZ - 1);
std::strncpy(ifr.ifr_name, ifname, IFNAMSIZ - 1);
ifr.ifr_name[IFNAMSIZ] = '\0';

<< " -> NG (no response)\n";
missing_ids.push_back(recv_can_ids[i]);
} else {
std::cout << "[arm#" << i << "] queried_mst_id: " << (uint32_t)mst
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should use static_cast in C++:

Suggested change
std::cout << "[arm#" << i << "] queried_mst_id: " << (uint32_t)mst
std::cout << "[arm#" << i << "] queried_mst_id: " << static_cast<uint32_t>(mst)

missing_ids.push_back(recv_can_ids[i]);
} else {
std::cout << "[arm#" << i << "] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
<< " queried_br: " << static_cast<int>(br) << " (" << br_label(static_cast<int>(br)) << ")\n";

Comment on lines +159 to +160
std::cout << "[gripper] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
std::cout << "[gripper] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
std::cout << "[gripper] queried_mst_id: " << static_cast<uint32_t>(mst)
<< " queried_br: " << static_cast<int>(br) << " (" << br_label(static_cast<int>(br)) << ")\n";

if (!missing_ids.empty()) {
std::cout << "NG: failed IDs:";
for (auto id : missing_ids) std::cout << " 0x" << std::hex << id;
std::cout << std::dec << "\n";
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

std::endl is better in C++:

Suggested change
std::cout << std::dec << "\n";
std::cout << std::dec << std::endl;

@gunyarakun gunyarakun requested a review from Copilot October 10, 2025 06:56
Copy link

@Copilot Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull Request Overview

This PR adds a new C++ diagnostic utility for OpenArm CAN communication. The tool helps diagnose CAN bus connectivity and motor configuration issues by querying motor parameters and providing detailed feedback on communication status.

  • Adds a comprehensive CAN diagnostic tool that detects interface mode and queries motor parameters
  • Integrates the new diagnostic executable into the CMake build system
  • Provides troubleshooting hints for common CAN communication issues

Reviewed Changes

Copilot reviewed 2 out of 2 changed files in this pull request and generated 5 comments.

File Description
setup/openarm_can_diagnosis.cpp New diagnostic utility that tests CAN interface configuration and motor communication
CMakeLists.txt Adds build configuration for the new openarm-diagnosis executable

Tip: Customize your code reviews with copilot-instructions.md. Create the file or learn how to get started.

Comment on lines +15 to +30
#include <linux/can.h>
#include <linux/can/raw.h>
#include <net/if.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <time.h>
#include <unistd.h>

#include <chrono>
#include <cmath>
#include <iostream>
#include <openarm/can/socket/openarm.hpp>
#include <openarm/damiao_motor/dm_motor_constants.hpp>
#include <thread>
#include <vector>
Copy link

Copilot AI Oct 10, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[nitpick] C system headers should be included before C++ headers. Move lines 15-22 after the C++ standard library headers (lines 24-30) to follow conventional include ordering.

Copilot uses AI. Check for mistakes.

return false; // fall back
}
struct ifreq ifr{};
std::strncpy(ifr.ifr_name, ifname, IFNAMSIZ - 1);
Copy link

Copilot AI Oct 10, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Using strncpy without null-termination guarantee. Consider using strcpy_s or ensure null termination by setting ifr.ifr_name[IFNAMSIZ - 1] = '\0' after the strncpy call.

Suggested change
std::strncpy(ifr.ifr_name, ifname, IFNAMSIZ - 1);
std::strncpy(ifr.ifr_name, ifname, IFNAMSIZ - 1);
ifr.ifr_name[IFNAMSIZ - 1] = '\0';

Copilot uses AI. Check for mistakes.

Comment on lines +135 to +161
for (size_t i = 0; i < arm_motors.size(); ++i) {
const auto& motor = arm_motors[i];
double mst = motor.get_param((int)openarm::damiao_motor::RID::MST_ID);
double br = motor.get_param((int)openarm::damiao_motor::RID::can_br);

if (mst < 0 || br < 0 || !std::isfinite(mst) || !std::isfinite(br)) {
std::cout << "[arm#" << i << "] id=0x" << std::hex << recv_can_ids[i] << std::dec
<< " -> NG (no response)\n";
missing_ids.push_back(recv_can_ids[i]);
} else {
std::cout << "[arm#" << i << "] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
}
}

for (size_t i = 0; i < gripper_motors.size(); ++i) {
const auto& gr = gripper_motors[i];
double mst = gr.get_param((int)openarm::damiao_motor::RID::MST_ID);
double br = gr.get_param((int)openarm::damiao_motor::RID::can_br);

if (mst < 0 || br < 0 || !std::isfinite(mst) || !std::isfinite(br)) {
std::cout << "[gripper] id=0x18 -> NG (no response)\n";
missing_ids.push_back(0x18);
} else {
std::cout << "[gripper] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
}
Copy link

Copilot AI Oct 10, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The motor parameter validation logic is duplicated between arm motors and gripper motors. Consider extracting this into a helper function to reduce code duplication.

Suggested change
for (size_t i = 0; i < arm_motors.size(); ++i) {
const auto& motor = arm_motors[i];
double mst = motor.get_param((int)openarm::damiao_motor::RID::MST_ID);
double br = motor.get_param((int)openarm::damiao_motor::RID::can_br);
if (mst < 0 || br < 0 || !std::isfinite(mst) || !std::isfinite(br)) {
std::cout << "[arm#" << i << "] id=0x" << std::hex << recv_can_ids[i] << std::dec
<< " -> NG (no response)\n";
missing_ids.push_back(recv_can_ids[i]);
} else {
std::cout << "[arm#" << i << "] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
}
}
for (size_t i = 0; i < gripper_motors.size(); ++i) {
const auto& gr = gripper_motors[i];
double mst = gr.get_param((int)openarm::damiao_motor::RID::MST_ID);
double br = gr.get_param((int)openarm::damiao_motor::RID::can_br);
if (mst < 0 || br < 0 || !std::isfinite(mst) || !std::isfinite(br)) {
std::cout << "[gripper] id=0x18 -> NG (no response)\n";
missing_ids.push_back(0x18);
} else {
std::cout << "[gripper] queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
}
// Helper function for motor parameter validation
auto validate_motor_param = [](const auto& motor, const std::string& label, uint32_t can_id, std::vector<uint32_t>& missing_ids) {
double mst = motor.get_param((int)openarm::damiao_motor::RID::MST_ID);
double br = motor.get_param((int)openarm::damiao_motor::RID::can_br);
if (mst < 0 || br < 0 || !std::isfinite(mst) || !std::isfinite(br)) {
std::cout << label << " id=0x" << std::hex << can_id << std::dec << " -> NG (no response)\n";
missing_ids.push_back(can_id);
} else {
std::cout << label << " queried_mst_id: " << (uint32_t)mst
<< " queried_br: " << (int)br << " (" << br_label((int)br) << ")\n";
}
};
for (size_t i = 0; i < arm_motors.size(); ++i) {
validate_motor_param(arm_motors[i], "[arm#" + std::to_string(i) + "]", recv_can_ids[i], missing_ids);
}
for (size_t i = 0; i < gripper_motors.size(); ++i) {
validate_motor_param(gripper_motors[i], "[gripper]", 0x18, missing_ids);

Copilot uses AI. Check for mistakes.

double mst = gr.get_param((int)openarm::damiao_motor::RID::MST_ID);
double br = gr.get_param((int)openarm::damiao_motor::RID::can_br);

if (mst < 0 || br < 0 || !std::isfinite(mst) || !std::isfinite(br)) {
Copy link

Copilot AI Oct 10, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The motor parameter validation logic is duplicated between arm motors and gripper motors. Consider extracting this into a helper function to reduce code duplication.

Copilot uses AI. Check for mistakes.

Comment on lines +156 to +157
std::cout << "[gripper] id=0x18 -> NG (no response)\n";
missing_ids.push_back(0x18);
Copy link

Copilot AI Oct 10, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The gripper CAN ID (0x18) is hardcoded and doesn't match the actual receive ID from the gripper initialization. Use the actual receive ID from the gripper motor configuration instead of the magic number.

Suggested change
std::cout << "[gripper] id=0x18 -> NG (no response)\n";
missing_ids.push_back(0x18);
std::cout << "[gripper] id=0x" << std::hex << gr.get_recv_can_id() << " -> NG (no response)\n";
missing_ids.push_back(gr.get_recv_can_id());

Copilot uses AI. Check for mistakes.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants