Skip to content

Conversation

@sugikazu75
Copy link
Member

@sugikazu75 sugikazu75 commented Sep 19, 2025

What is this

enable to use different type motors for thrust.

Details

  • add new message in spinal PwmInfos which have motor type array to specify motor if necessary. And it have motor_infos field to store all type of motors.
  • update interface of spinal and aeiral_robot_control
  • update saturation process implemented in attitude control of spinal considering each profile of motors

No change is needed if we use single type of motor.

TODO

  • check with real machine with single type of motor
  • check with real machine with multiple types of motor

@sugikazu75 sugikazu75 requested a review from sawa3030 September 19, 2025 14:03
@sugikazu75
Copy link
Member Author

usage

MotorInfo.yaml example

motor_info: 
        motor_types: [0, 0, 0, 0, 1]
        min_pwm: 0.59 # 1180 [ms]
        max_pwm: 0.9375 # 1875 [ms]
        min_thrust: 1.0 #  [N]
        force_landing_thrust: 6.5 #[N]
        m_f_rate: -0.0172
        pwm_conversion_mode: 0 # SQRT Mode
        vel_ref_num: 1
        ref1:
                voltage: 25.2
                max_thrust: 20 # N 
                polynominal2: 0.07983707 # x10
                polynominal1: -6.627443098 # x10
                polynominal0: 12.3593793002 # x1

motor_info1:
        min_pwm: 0.55 # = 1100 [ms]
        max_pwm: 0.92 # = 1840 [ms]
        min_thrust: 0 # [N]
        force_landing_thrust: 13 #[N]
        pwm_conversion_mode: 1 # Polynominal Mode
        vel_ref_num: 4
        ref1:        
                voltage: 25.2
                max_thrust: 21.1 # N < max is 21.20V (60.5 A), but currency max of ESC is 60 A,
                polynominal4: 3.0281784 # x 10^4, 7 decimal places (total 8 decimal places)
                polynominal3: -12.648033 # x10^3, 6 decimal places (total 8 decimal places)
                polynominal2: 12.444642 # x10^2,  6 decimal places (total 8 decimal places)
                polynominal1: 19.748675 # x10,    6 decimal places (total 8 decimal places)
                polynominal0: 51.760116 # x1,     6 decimal places (total 8 decimal places)

motor_info/motor_types identify the type of motor for each thruster.
Information under motor_info is used for 0-th motor and motor_infoN is used for N-th motor.

@sugikazu75 sugikazu75 requested a review from Copilot September 23, 2025 08:35
Copy link

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 support for multiple types of thrust motors in the spinal control system. The change enables using different motor types for thrust rather than being limited to a single motor type.

  • Adds new PwmInfos message containing motor type arrays and motor_infos field for different motor types
  • Updates URDF files to use effort value from joint limits for motor-specific m_f_rate values
  • Implements per-motor PWM conversion, saturation checking, and thrust limits in attitude control

Reviewed Changes

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

Show a summary per file
File Description
aerial_robot_nerve/spinal/msg/PwmInfos.msg New message type defining motor types array and PWM info array
aerial_robot_nerve/spinal/mcu_project/lib/Jsk_Lib/flight_control/attitude/attitude_control.h Updated to handle multiple motor types with per-motor arrays
aerial_robot_nerve/spinal/mcu_project/lib/Jsk_Lib/flight_control/attitude/attitude_control.cpp Implements per-motor PWM conversion and saturation logic
aerial_robot_control/include/aerial_robot_control/control/base/base.h Updates control interface to support multiple motor types
aerial_robot_model/include/aerial_robot_model/model/aerial_robot_model.h Changes thrust limits and m_f_rate to per-motor arrays
aerial_robot_model/src/model/base_model/robot_model.cpp Implements per-motor property extraction from URDF
robots//urdf/.urdf.xacro Sets effort limit to 0 to enable motor-specific m_f_rate from URDF
aerial_robot_simulation/include/aerial_robot_simulation/rotor_handle.h Uses effort value from URDF for motor-specific m_f_rate

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

Comment on lines +1078 to +1079
float yaw_decreasing_rate_i = residual_term / (fabs(yaw_term_[i]) / rotor_devider_);
if(yaw_decreasing_rate_i < yaw_decreasing_rate) yaw_decreasing_rate = yaw_decreasing_rate_i;
Copy link

Copilot AI Sep 23, 2025

Choose a reason for hiding this comment

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

Potential division by zero when yaw_term_[i] is zero. This could occur when yaw control is not active or when the yaw term is exactly zero, leading to undefined behavior.

Suggested change
float yaw_decreasing_rate_i = residual_term / (fabs(yaw_term_[i]) / rotor_devider_);
if(yaw_decreasing_rate_i < yaw_decreasing_rate) yaw_decreasing_rate = yaw_decreasing_rate_i;
if (fabs(yaw_term_[i]) > 1e-6) // prevent division by zero
{
float yaw_decreasing_rate_i = residual_term / (fabs(yaw_term_[i]) / rotor_devider_);
if(yaw_decreasing_rate_i < yaw_decreasing_rate) yaw_decreasing_rate = yaw_decreasing_rate_i;
}
// else: skip update to yaw_decreasing_rate to avoid division by zero

Copilot uses AI. Check for mistakes.
Copy link

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.

Copilot encountered an error and was unable to review this pull request. You can try again by re-requesting a review.

@sugikazu75
Copy link
Member Author

I found that generated message for nested array is incorrectly deserialized and this implementation did not work for real machine.
Related to ros-drivers/rosserial#314 (comment)

@sugikazu75
Copy link
Member Author

I found that generated message for nested array is incorrectly deserialized and this implementation did not work for real machine. Related to ros-drivers/rosserial#314 (comment)

This problem has been solved by sugikazu75/rosserial@eb8c359

@sugikazu75 sugikazu75 marked this pull request as ready for review December 8, 2025 07:14
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.

1 participant