Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enable visualizing the rotor speed in gazebo #500

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ namespace hardware_interface

motor_nh.param("rotor_force_noise", rotor_force_noise_, 0.0); // N
motor_nh.param("dual_rotor_moment_noise", dual_rotor_moment_noise_, 0.0);
motor_nh.param("speed_rate", speed_rate_, 1.0); // rad/s/N , this is a virtual linear rate of speed-f
}

inline std::string getName() const {return name_;}
Expand All @@ -102,13 +103,19 @@ namespace hardware_interface
}
inline void setCommand(double command); //no implement here

inline double getSpeed() const
{
return *force_ * speed_rate_;
}

private:
std::string name_;
boost::shared_ptr<double> force_;
int direction_;
double f_pwm_rate_;
double f_pwm_offset_;
double m_f_rate_;
double speed_rate_;
double pwm_rate_;
double max_pwm_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,8 @@ namespace rotor_limits_interface
*/
void enforceLimits(const ros::Duration& /* period */)
{
if(jh_.getForce() == 0) return;

/* because of "inline double setForce(double force) {*force_ = force;}", we can change the value with same address */
jh_.setForce(internal::saturate(jh_.getForce(), min_force_, max_force_));
}
Expand Down
1 change: 1 addition & 0 deletions aerial_robot_simulation/src/aerial_robot_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -376,6 +376,7 @@ namespace gazebo_ros_control
auto torque = rotor.getTorque();
parent_link->AddRelativeTorque(gazebo::math::Vector3(torque.x(), torque.y(), torque.z()));
#endif
sim_rotors_.at(j)->SetVelocity(0, rotor.getSpeed());
}
}
}
Expand Down
13 changes: 12 additions & 1 deletion robots/hydrus/urdf/link.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@
</xacro:unless>
</xacro:if>
<xacro:unless value="${tilt_mode == 1}">
<origin rpy="0 0 0" xyz="${link_length* 0.5} 0 0"/>
<origin rpy="0 0 0" xyz="${link_length* 0.5} 0 0.013"/>
</xacro:unless>
<axis xyz="0 0 ${rotor_direction}"/>
</joint>
Expand All @@ -233,6 +233,17 @@
<cylinder length="0.1" radius="${protector_radius + 0.01}"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.032"/>
<geometry>
<xacro:if value="${rotor_direction == 1}">
<mesh filename="package://hydrus/urdf/mesh/propeller/T-motor-CF-14inch-CCW.dae"/>
</xacro:if>
<xacro:if value="${rotor_direction == -1}">
<mesh filename="package://hydrus/urdf/mesh/propeller/T-motor-CF-14inch-CW.dae"/>
</xacro:if>
</geometry>
</visual>
</link>
<xacro:damping_factor link ="thrust${self}"/>

Expand Down
234 changes: 234 additions & 0 deletions robots/hydrus/urdf/mesh/propeller/T-motor-CF-14inch-CCW.dae

Large diffs are not rendered by default.

162 changes: 162 additions & 0 deletions robots/hydrus/urdf/mesh/propeller/T-motor-CF-14inch-CW.dae

Large diffs are not rendered by default.

280 changes: 89 additions & 191 deletions robots/hydrus/urdf/mesh/ver1/link/end_link.dae

Large diffs are not rendered by default.

282 changes: 90 additions & 192 deletions robots/hydrus/urdf/mesh/ver1/link/general_link.dae

Large diffs are not rendered by default.

282 changes: 90 additions & 192 deletions robots/hydrus/urdf/mesh/ver1/link/head_link.dae

Large diffs are not rendered by default.

261 changes: 115 additions & 146 deletions robots/hydrus/urdf/mesh/ver2/link/link1.dae

Large diffs are not rendered by default.

277 changes: 123 additions & 154 deletions robots/hydrus/urdf/mesh/ver2/link/link2.dae

Large diffs are not rendered by default.

277 changes: 123 additions & 154 deletions robots/hydrus/urdf/mesh/ver2/link/link3.dae

Large diffs are not rendered by default.

275 changes: 122 additions & 153 deletions robots/hydrus/urdf/mesh/ver2/link/link4.dae

Large diffs are not rendered by default.

241 changes: 105 additions & 136 deletions robots/hydrus/urdf/mesh/ver2/link/tilt_10deg_15inch_link1.dae

Large diffs are not rendered by default.

273 changes: 108 additions & 165 deletions robots/hydrus/urdf/mesh/ver2/link/tilt_10deg_15inch_link2.dae

Large diffs are not rendered by default.

Loading
Loading