Motor Power output, SITL

Hi,
I want to change the weight (mass) of my model in the SITL, from 1.5kg to say about 3~4kg with a 4s. how do i change the gazebo motor parameters accordingly? in the SDF: what are units of motorconstant? etc?
My guess is that its the following to changeā€¦ what is the motor power parameter in VTOL?

</plugin>
    <plugin name='front_right_motor_model' filename='librotors_gazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_0_joint</jointName>
      <linkName>rotor_0</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>838</maxRotVelocity>      
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>0</motorNumber>
      <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
-----------------------
standard vtol uses the same motor with:
<maxRotVelocity>1100</maxRotVelocity>

standard vtol has an additional pusher motor with:
      <maxRotVelocity>3000</maxRotVelocity>
      <momentConstant>0.01</momentConstant>

plane has one motor with:
     <maxRotVelocity>3100</maxRotVelocity>
      <momentConstant>0.01</momentConstant>

prop config:

----rotor config-----
   <link name='rotor_0'>
      <pose>0.3 -0.3 0.4 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000166704</iyy>
          <iyz>0</iyz>
          <izz>0.000167604</izz>
        </inertia>

----------------------
one more parameter in the VOTL application, changing this did not show any effect:
/**
 * Motor max power
 *
 * Indicates the maximum power the motor is able to produce. Used to calculate
 * propeller efficiency map.
 *
 * @unit W
 * @min 1
 * @max 10000
 * @increment 1
 * @decimal 0
 * @group VTOL Attitude Control
 */
PARAM_DEFINE_FLOAT(VT_POWER_MAX, 120.0f);

Hi,

The motor constant defines the relationship between produced thrust and rotational speed of your
rotor.
The relation is
thrust = rot_speed*rot_speed * motor_constant

So the units are N * s^2

That parameter you found (VT_POWER_MAX) will have no effect. Itā€™s used to calculate the
propeller slipstream velocity for tailsitters.

1 Like

Hi Tumbili,
Thanksā€¦
btw. got the vtol tailsitter flying full missions in SITL :smiley:

Velocity is in rads per second?

Correct. Damn messge telling me the post must have at least 20 characters.

Thanksā€¦ lolā€¦ sorted all the motor issuesā€¦ now to change the wingā€¦ :smiley:

Can the rigging angle of the wing be changed by forward and upward parameters in the SDF in liftdrag?

@Arjuna.Mendis In the sdf file which includes the wings for the plane you should be able to specify the orientation of each wing in terms of forward and up axis I think.

Hi, All is well, managed to change wing parameters etc. except I need to increase the body velocity to reach about 30~35 m/s and I found these parameters
FW_AIRSPD_TRIM
FW_AIRSPD_MIN
FW_AIRSPD_MAX
and a line of code in the gazebo_motor_model.cpp:
double scalar = 1 - vel / 25; // at 50 m/s the rotor will not produce any force anymore
Setting the FW parameters does not allow the velocity to be changed drastically. Iā€™m not entirely sure why 25 is hard coded in the above line of code

Thanks

@Arjuna.Mendis This is a hack! The reason for this was to account for the fact that a propeller will produce less thrust when the air inflow becomes larger. The linear relation is not correct, one could use better approximations. Why donā€™t you implement something more realistic in terms or parameters which have to be specified in the sdf file when attaching a motor/propeller to the model?

Lolā€¦thanksā€¦will give it a goā€¦

@Arjuna.Mendis That would be fantastic, looking forward to it!

Hey Guys ! Iā€™m trying to simulate a tricopter with a tiltrotor(servo). I set channels in the following manner:

[1] - Front Right
[2] - Front Left
[3] - Back motor
[4] - servo

I have modified the init/ekf2/file to use the Y+ mixer file (Rest are same as IRIS file). In the SDF if I remove the channel 4, The all three main rotors arm properly. But when I add channel 4 for servo (Copied code from plane SDF), the back motor doesnt arm (But the servo does though). Mind helping me out ?

@ganeshrk95 can you create a new post to discuss? Please share your mixer files as well.

Hiā€¦i am a new user here. As per my knowledge an electric motor will try to maintain the kv regardless of load. The torque is determined by how many poles and kv. Higher pole count and lower kv will produce more torque allowing you to spin a bigger prop. Power output is affected directly from load, if you put a larger prop the motor will pull more current to try to maintain the kv. Volts x amps = watts. So depending on the prop you wish to turn you should select the power train not the other way around.

pcb assembly supplier