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

Allow referencing links in nested models in LiftDrag #955

Merged
merged 3 commits into from
Aug 10, 2021
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
293 changes: 293 additions & 0 deletions examples/worlds/lift_drag_nested.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,293 @@
<?xml version="1.0" ?>
<!--
This is the same example as lift_drag.sdf but modified to show that links in
nested models can be references in the link_name parameter.

This file was adapted from osrf/gazebo/worlds/single_rotor_demo.world

Try sending commands:

ign topic -t "/model/lift_drag_demo_model/joint/rod_1_joint/cmd_force" -m ignition.msgs.Double -p "data: 0.7"

Listen to joint states:

ign topic -e -t /world/lift_drag/model/lift_drag_demo_model/joint_state

-->
<sdf version="1.8">
<world name="lift_drag">
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="lift_drag_demo_model">
<pose>0 0 0 0 0 0</pose>
<link name="body">
<pose>0.0 0 0.5 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1.8</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1.8</iyy>
<iyz>0.0</iyz>
<izz>1.8</izz>
</inertia>
<mass>10.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.1</mu>
<mu2>0.1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="rod_1">
<pose>0 0 1.25 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.012</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.012</iyy>
<iyz>0.0</iyz>
<izz>0.0012</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.02 0.02 0.5</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.02 0.02 0.5</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<model name="blade_1">
<link name="link">
<pose>0 0 1.5 0.0 0 0</pose>
<inertial>
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.5 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
</model>
<model name="blade_2">
<link name="link">
<pose>0 0 1.5 0.0 0 3.141593</pose>
<inertial>
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.2 0.5 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
</model>
<joint name="rod_1_joint" type="revolute">
<parent>body</parent>
<child>rod_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
</limit>
<xyz>0.0 0.0 -1.0</xyz>
<dynamics>
<damping>0.0001</damping>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_1_joint" type="fixed">
<parent>rod_1</parent>
<child>blade_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
</joint>
<joint name="blade_2_joint" type="fixed">
<parent>rod_1</parent>
<child>blade_2</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
</joint>

<plugin
filename="ignition-gazebo-joint-state-publisher-system"
name="ignition::gazebo::systems::JointStatePublisher"></plugin>

<plugin
filename="ignition-gazebo-lift-drag-system"
name="ignition::gazebo::systems::LiftDrag">
<a0>0.1</a0>
<cla>0.1</cla>
<cda>0.001</cda>
<cma>0.0</cma>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>blade_1::link</link_name>
</plugin>
<plugin
filename="ignition-gazebo-lift-drag-system"
name="ignition::gazebo::systems::LiftDrag">
<a0>0.1</a0>
<cla>0.1</cla>
<cda>0.001</cda>
<cma>0.0</cma>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>blade_2::link</link_name>
</plugin>
<plugin
filename="ignition-gazebo-apply-joint-force-system"
name="ignition::gazebo::systems::ApplyJointForce">
<joint_name>rod_1_joint</joint_name>
</plugin>
</model>
</world>
</sdf>
47 changes: 41 additions & 6 deletions src/systems/lift_drag/LiftDrag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/Inertial.hh"
#include "ignition/gazebo/components/Joint.hh"
#include "ignition/gazebo/components/JointPosition.hh"
#include "ignition/gazebo/components/LinearVelocity.hh"
#include "ignition/gazebo/components/Link.hh"
Expand Down Expand Up @@ -172,33 +173,67 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm,
{
sdf::ElementPtr elem = _sdf->GetElement("link_name");
auto linkName = elem->Get<std::string>();
this->linkEntity = this->model.LinkByName(_ecm, linkName);
auto entities =
entitiesFromScopedName(linkName, _ecm, this->model.Entity());

if (this->linkEntity == kNullEntity)
if (entities.empty())
{
ignerr << "Link with name[" << linkName << "] not found. "
<< "The LiftDrag will not generate forces\n";
this->validConfig = false;
return;
}
else if (entities.size() > 1)
{
ignwarn << "Multiple link entities with name[" << linkName << "] found. "
<< "Using the first one.\n";
}

this->linkEntity = *entities.begin();
if (!_ecm.EntityHasComponentType(this->linkEntity,
components::Link::typeId))
{
this->linkEntity = kNullEntity;
ignerr << "Entity with name[" << linkName << "] is not a link\n";
this->validConfig = false;
return;
}
}
else
{
ignerr << "The LiftDrag system requires the 'link_name' parameter\n";
this->validConfig = false;
return;
}


if (_sdf->HasElement("control_joint_name"))
jennuine marked this conversation as resolved.
Show resolved Hide resolved
{
auto controlJointName = _sdf->Get<std::string>("control_joint_name");
this->controlJointEntity = this->model.JointByName(_ecm, controlJointName);
if (this->controlJointEntity == kNullEntity)
auto entities =
entitiesFromScopedName(controlJointName, _ecm, this->model.Entity());

if (entities.empty())
{
ignerr << "Joint with name[" << controlJointName << "] not found. "
<< "The LiftDrag will not generate forces\n";
this->validConfig = false;
return;
}
else if (entities.size() > 1)
{
ignerr << "Joint with name[" << controlJointName << "] does not exist.\n";
ignwarn << "Multiple joint entities with name[" << controlJointName
<< "] found. Using the first one.\n";
}
else

this->controlJointEntity = *entities.begin();
if (!_ecm.EntityHasComponentType(this->controlJointEntity,
components::Joint::typeId))
{
this->controlJointEntity = kNullEntity;
ignerr << "Entity with name[" << controlJointName << "] is not a joint\n";
this->validConfig = false;
return;
}
}

Expand Down
6 changes: 5 additions & 1 deletion src/systems/lift_drag/LiftDrag.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,9 @@ namespace systems
/// The following parameters are used by the system:
///
/// link_name : Name of the link affected by the group of lift/drag
/// properties.
/// properties. This can be a scoped name to reference links in
azeey marked this conversation as resolved.
Show resolved Hide resolved
/// nested models. \sa entitiesFromScopedName to learn more
/// about scoped names.
/// air_density : Density of the fluid this model is suspended in.
/// area : Surface area of the link.
/// a0 : The initial "alpha" or initial angle of attack. a0 is also
Expand All @@ -59,6 +61,8 @@ namespace systems
/// coefficient curve.
/// cda_stall : The ratio of coefficient of drag and alpha slope after
/// stall.
/// control_joint_name: Name of joint that actuates a control surface for this
/// lifting body (Optional)
class LiftDrag
: public System,
public ISystemConfigure,
Expand Down
Loading