Skip to content

Commit

Permalink
Merge branch 'main' into chapulina/flip_thruster
Browse files Browse the repository at this point in the history
  • Loading branch information
chapulina committed Nov 16, 2021
2 parents 540af70 + 74e76ed commit dd0a815
Show file tree
Hide file tree
Showing 8 changed files with 203 additions and 8 deletions.
9 changes: 7 additions & 2 deletions lrauv_description/models/tethys_equipped/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,10 @@
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<!-- Link's Y is perpendicular to the control surface -->
<upward>0 1 0</upward>
<forward>1 0 0</forward>
<!-- Link's X is pointing towards the back -->
<forward>-1 0 0</forward>
<link_name>vertical_fins</link_name>
<cp>0 0 0</cp>
</plugin>
Expand All @@ -136,8 +138,10 @@
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<!-- Link's Z is perpendicular to the control surface -->
<upward>0 0 1</upward>
<forward>1 0 0</forward>
<!-- Link's X is pointing towards the back -->
<forward>-1 0 0</forward>
<link_name>horizontal_fins</link_name>
<cp>0 0 0</cp>
</plugin>
Expand All @@ -148,6 +152,7 @@
<namespace>tethys</namespace>
<command_topic>tethys/command_topic</command_topic>
<state_topic>tethys/state_topic</state_topic>
<debug_printout>0</debug_printout>
</plugin>
<plugin
filename="HydrodynamicsPlugin"
Expand Down
2 changes: 2 additions & 0 deletions lrauv_ignition_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@ install(
foreach(EXAMPLE
example_buoyancy
example_controller
example_elevator
example_mass_shifter
example_rudder
example_spawn
Expand Down Expand Up @@ -236,6 +237,7 @@ if(BUILD_TESTING)
test_buoyancy_action
test_controller
test_drop_weight
test_elevator
test_mass_shifter
test_mission_depth_vbs
test_mission_pitch_mass
Expand Down
70 changes: 70 additions & 0 deletions lrauv_ignition_plugins/example/example_elevator.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

/**
* Control the elevator joint position.
*
* Positive angles rotate the horizontal fins counter-clockwise when looking
* from starboard, which makes the vehicle go down when propelled forward.
* Negative commands do the opposite.
*
* Usage:
* $ LRAUV_example_elevator <vehicle_name> <angle_radians>
*/
#include <chrono>
#include <thread>

#include <ignition/msgs.hh>
#include <ignition/transport.hh>
#include "lrauv_command.pb.h"

int main(int _argc, char **_argv)
{
std::string vehicleName("tethys");
if (_argc > 1)
{
vehicleName = _argv[1];
}

double angle{0.17};
if (_argc > 2)
{
angle = atof(_argv[2]);
}

ignition::transport::Node node;
auto commandTopic = "/" + vehicleName + "/command_topic";
auto commandPub =
node.Advertise<lrauv_ignition_plugins::msgs::LRAUVCommand>(commandTopic);

while (!commandPub.HasConnections())
{
std::cout << "Command publisher waiting for connections..." << std::endl;
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
}

lrauv_ignition_plugins::msgs::LRAUVCommand cmdMsg;
cmdMsg.set_elevatorangleaction_(angle);

// Keep it stable
cmdMsg.set_buoyancyaction_(0.0005);
cmdMsg.set_dropweightstate_(1);

commandPub.Publish(cmdMsg);

std::cout << "Moving elevator to [" << angle << "] rad" << std::endl;
}
13 changes: 11 additions & 2 deletions lrauv_ignition_plugins/proto/lrauv_command.proto
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,12 @@ message LRAUVCommand
// Higher values have the vertical fins
// rotated more clockwise when looking
// from the top (i.e. to starboard)
float elevatorAngle_ = 4;
float elevatorAngle_ = 4; // Angle that the controller believes the
// elevator is currently at. Unit: radians.
// Higher values have the horizontal fins
// rotated more counter-clockwise when
// looking from starboard, which tilts the
// nose downward when moving forward.
float massPosition_ = 5; // Position where the controller believes
// the mass shifter's joint is in. Unit:
// meters. Positive values have the battery
Expand All @@ -69,7 +74,11 @@ message LRAUVCommand
// radians. Higher values rotate the
// vertical fins clockwise when looking
// from the top (i.e. to starboard)
float elevatorAngleAction_ = 10;
float elevatorAngleAction_ = 10; // Target angle for the elevator joint.
// Unit: radians. Higher values rotate
// vertical fins more counter-clockwise
// when looking from starboard, which tilts
// the nose downward when moving forward.
float massPositionAction_ = 11; // Target position for the battery's joint.
// Unit: meters. Positive values move the
// battery forward, tilting the nose
Expand Down
25 changes: 24 additions & 1 deletion lrauv_ignition_plugins/src/ScienceSensorsSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,10 @@

#include <ignition/msgs/pointcloud_packed.pb.h>

#include <ignition/plugin/Register.hh>
#include <ignition/common/SystemPaths.hh>
#include <ignition/gazebo/World.hh>
#include <ignition/msgs/Utility.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/transport/Node.hh>

#include <pcl/conversions.h>
Expand Down Expand Up @@ -142,6 +143,15 @@ class tethys::ScienceSensorsSystemPrivate
public: std::vector<pcl::octree::OctreePointCloudSearch<pcl::PointXYZ>>
spatialOctrees;

/// \brief Set to true after the spherical coordinates have been initialized.
/// This may happen at startup if the SDF file has them hardcoded, or at
/// runtime when the first vehicle is spawned. Assume the coordinates are
/// only shifted once.
public: bool sphericalCoordinatesInitialized{false};

/// \brief World object to access world properties.
public: ignition::gazebo::World world;

/// \brief Node for communication
public: ignition::transport::Node node;

Expand Down Expand Up @@ -480,6 +490,8 @@ void ScienceSensorsSystem::Configure(
ignition::gazebo::EntityComponentManager &_ecm,
ignition::gazebo::EventManager &_eventMgr)
{
this->dataPtr->world = ignition::gazebo::World(_entity);

if (_sdf->HasElement("data_path"))
{
this->dataPtr->dataPath = _sdf->Get<std::string>("data_path");
Expand Down Expand Up @@ -516,6 +528,17 @@ void ScienceSensorsSystem::PreUpdate(
const ignition::gazebo::UpdateInfo &,
ignition::gazebo::EntityComponentManager &_ecm)
{
if (!this->dataPtr->sphericalCoordinatesInitialized)
{
auto latLon = this->dataPtr->world.SphericalCoordinates(_ecm);
if (latLon)
{
ignwarn << "New spherical coordinates detected." << std::endl;
//TODO(chapulina) Shift science data to new coordinates
this->dataPtr->sphericalCoordinatesInitialized = true;
}
}

_ecm.EachNew<ignition::gazebo::components::CustomSensor,
ignition::gazebo::components::ParentEntity>(
[&](const ignition::gazebo::Entity &_entity,
Expand Down
12 changes: 9 additions & 3 deletions lrauv_ignition_plugins/src/TethysCommPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -198,13 +198,17 @@ void TethysCommPlugin::Configure(
{
this->stateTopic = _sdf->Get<std::string>("state_topic");
}
if (_sdf->HasElement("debug_printout"))
{
this->debugPrintout = _sdf->Get<bool>("debug_printout");
}

// Initialize transport
if (!this->node.Subscribe(this->commandTopic,
&TethysCommPlugin::CommandCallback, this))
{
ignerr << "Error subscribing to topic " << "[" << this->commandTopic << "]. "
<< std::endl;
ignerr << "Error subscribing to topic " << "[" << this->commandTopic
<< "]. " << std::endl;
return;
}

Expand Down Expand Up @@ -389,6 +393,7 @@ void TethysCommPlugin::CommandCallback(
// Lazy timestamp conversion just for printing
//if (std::chrono::seconds(int(floor(_msg.time_()))) - this->prevSubPrintTime
// > std::chrono::milliseconds(1000))
if (this->debugPrintout)
{
igndbg << "[" << this->ns << "] Received command: " << std::endl
<< _msg.DebugString() << std::endl;
Expand Down Expand Up @@ -604,7 +609,8 @@ void TethysCommPlugin::PostUpdate(

this->statePub.Publish(stateMsg);

if (_info.simTime - this->prevPubPrintTime > std::chrono::milliseconds(1000))
if (this->debugPrintout &&
_info.simTime - this->prevPubPrintTime > std::chrono::milliseconds(1000))
{
igndbg << "[" << this->ns << "] Published state to " << this->stateTopic
<< " at time: " << stateMsg.header().stamp().sec()
Expand Down
3 changes: 3 additions & 0 deletions lrauv_ignition_plugins/src/TethysCommPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,9 @@ namespace tethys
/// \param[in] _ns Namespace to prepend to topic names
private: void SetupControlTopics(const std::string &_ns);

/// Enable debug printout
private: bool debugPrintout = false;

/// Namespace for topics.
private: std::string ns{""};

Expand Down
77 changes: 77 additions & 0 deletions lrauv_ignition_plugins/test/test_elevator.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <chrono>
#include <gtest/gtest.h>

#include "helper/LrauvTestFixture.hh"
#include "lrauv_command.pb.h"

#include <fstream>

//////////////////////////////////////////////////
TEST_F(LrauvTestFixture, Elevator)
{
this->fixture->Server()->Run(true, 100, false);
EXPECT_EQ(100, this->iterations);
EXPECT_EQ(100, this->tethysPoses.size());
EXPECT_NEAR(0.0, this->tethysPoses.back().Pos().X(), 1e-6);
EXPECT_NEAR(0.0, this->tethysPoses.back().Pos().Y(), 1e-6);
EXPECT_NEAR(0.0, this->tethysPoses.back().Pos().Z(), 2e-2);

// Propel vehicle
lrauv_ignition_plugins::msgs::LRAUVCommand cmdMsg;

// Move forward
cmdMsg.set_propomegaaction_(30);

// Rotate elevator counter-clockwise when looking from starboard, which
// causes the vehicle to pitch down
// Using an angle lower than the stall angle 0.17
cmdMsg.set_elevatorangleaction_(0.15);

// Neutral buoyancy
cmdMsg.set_buoyancyaction_(0.0005);
cmdMsg.set_dropweightstate_(true);

// Run server until the command is processed and the model reaches a certain
// point vertically
double targetZ{-1.5};
this->PublishCommandWhile(cmdMsg, [&]()
{
return this->tethysPoses.back().Pos().Z() > targetZ;
});

EXPECT_LT(1500, this->iterations);
EXPECT_LT(1500, this->tethysPoses.size());

// Vehicle goes down
EXPECT_GT(targetZ, this->tethysPoses.back().Pos().Z());

for (int i = 0; i < this->tethysPoses.size(); ++i)
{
auto pose = this->tethysPoses[i];

// FIXME(chapulina) It goes up a little bit in the beginning, is this
// expected?
if (i < 1500)
EXPECT_GT(0.2, pose.Pos().Z()) << i << " -- " << pose.Pos().Z();
else
EXPECT_GT(0.0, pose.Pos().Z()) << i << " -- " << pose.Pos().Z();
}
}

0 comments on commit dd0a815

Please sign in to comment.