-
Notifications
You must be signed in to change notification settings - Fork 58
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge branch 'main' of https://github.com/ignitionrobotics/ign-sensors …
…into Segmentation Signed-off-by: AmrElsersy <amrelsersay@gmail.com>
- Loading branch information
Showing
61 changed files
with
1,221 additions
and
949 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) | ||
|
||
project(odometer) | ||
|
||
find_package(ignition-cmake2 REQUIRED) | ||
find_package(ignition-sensors6 REQUIRED) | ||
|
||
add_library(${PROJECT_NAME} SHARED Odometer.cc) | ||
target_link_libraries(${PROJECT_NAME} | ||
PUBLIC ignition-sensors6::ignition-sensors6) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,109 @@ | ||
/* | ||
* 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 <math.h> | ||
|
||
#include <ignition/msgs/double.pb.h> | ||
|
||
#include <ignition/common/Console.hh> | ||
#include <ignition/sensors/Noise.hh> | ||
#include <ignition/sensors/Util.hh> | ||
|
||
#include "Odometer.hh" | ||
|
||
using namespace custom; | ||
|
||
////////////////////////////////////////////////// | ||
bool Odometer::Load(const sdf::Sensor &_sdf) | ||
{ | ||
auto type = ignition::sensors::customType(_sdf); | ||
if ("odometer" != type) | ||
{ | ||
ignerr << "Trying to load [odometer] sensor, but got type [" | ||
<< type << "] instead." << std::endl; | ||
return false; | ||
} | ||
|
||
// Load common sensor params | ||
ignition::sensors::Sensor::Load(_sdf); | ||
|
||
// Advertise topic where data will be published | ||
this->pub = this->node.Advertise<ignition::msgs::Double>(this->Topic()); | ||
|
||
if (!_sdf.Element()->HasElement("ignition:odometer")) | ||
{ | ||
igndbg << "No custom configuration for [" << this->Topic() << "]" | ||
<< std::endl; | ||
return true; | ||
} | ||
|
||
// Load custom sensor params | ||
auto customElem = _sdf.Element()->GetElement("ignition:odometer"); | ||
|
||
if (!customElem->HasElement("noise")) | ||
{ | ||
igndbg << "No noise for [" << this->Topic() << "]" << std::endl; | ||
return true; | ||
} | ||
|
||
sdf::Noise noiseSdf; | ||
noiseSdf.Load(customElem->GetElement("noise")); | ||
this->noise = ignition::sensors::NoiseFactory::NewNoiseModel(noiseSdf); | ||
if (nullptr == this->noise) | ||
{ | ||
ignerr << "Failed to load noise." << std::endl; | ||
return false; | ||
} | ||
|
||
return true; | ||
} | ||
|
||
////////////////////////////////////////////////// | ||
bool Odometer::Update(const std::chrono::steady_clock::duration &_now) | ||
{ | ||
ignition::msgs::Double msg; | ||
*msg.mutable_header()->mutable_stamp() = ignition::msgs::Convert(_now); | ||
auto frame = msg.mutable_header()->add_data(); | ||
frame->set_key("frame_id"); | ||
frame->add_value(this->Name()); | ||
|
||
this->totalDistance = this->noise->Apply(this->totalDistance); | ||
|
||
msg.set_data(this->totalDistance); | ||
|
||
this->AddSequence(msg.mutable_header()); | ||
this->pub.Publish(msg); | ||
|
||
return true; | ||
} | ||
|
||
////////////////////////////////////////////////// | ||
void Odometer::NewPosition(const ignition::math::Vector3d &_pos) | ||
{ | ||
if (!isnan(this->prevPos.X())) | ||
{ | ||
this->totalDistance += this->prevPos.Distance(_pos); | ||
} | ||
this->prevPos = _pos; | ||
} | ||
|
||
////////////////////////////////////////////////// | ||
const ignition::math::Vector3d &Odometer::Position() const | ||
{ | ||
return this->prevPos; | ||
} | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
/* | ||
* 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. | ||
* | ||
*/ | ||
#ifndef ODOMETER_HH_ | ||
#define ODOMETER_HH_ | ||
|
||
#include <ignition/sensors/Sensor.hh> | ||
#include <ignition/sensors/SensorTypes.hh> | ||
#include <ignition/transport/Node.hh> | ||
|
||
namespace custom | ||
{ | ||
/// \brief Example sensor that publishes the total distance travelled by a | ||
/// robot, with noise. | ||
class Odometer : public ignition::sensors::Sensor | ||
{ | ||
/// \brief Load the sensor with SDF parameters. | ||
/// \param[in] _sdf SDF Sensor parameters. | ||
/// \return True if loading was successful | ||
public: virtual bool Load(const sdf::Sensor &_sdf) override; | ||
|
||
/// \brief Update the sensor and generate data | ||
/// \param[in] _now The current time | ||
/// \return True if the update was successfull | ||
public: virtual bool Update( | ||
const std::chrono::steady_clock::duration &_now) override; | ||
|
||
/// \brief Set the current postiion of the robot, so the odometer can | ||
/// calculate the distance travelled. | ||
/// \param[in] _pos Current position in world coordinates. | ||
public: void NewPosition(const ignition::math::Vector3d &_pos); | ||
|
||
/// \brief Get the latest world postiion of the robot. | ||
/// \return The latest position given to the odometer. | ||
public: const ignition::math::Vector3d &Position() const; | ||
|
||
/// \brief Previous position of the robot. | ||
private: ignition::math::Vector3d prevPos{std::nan(""), std::nan(""), | ||
std::nan("")}; | ||
|
||
/// \brief Latest total distance. | ||
private: double totalDistance{0.0}; | ||
|
||
/// \brief Noise that will be applied to the sensor data | ||
private: ignition::sensors::NoisePtr noise{nullptr}; | ||
|
||
/// \brief Node for communication | ||
private: ignition::transport::Node node; | ||
|
||
/// \brief Publishes sensor data | ||
private: ignition::transport::Node::Publisher pub; | ||
}; | ||
} | ||
|
||
#endif |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,38 @@ | ||
# Custom sensor | ||
|
||
This example creates a simple custom sensor called `Odometer`, which | ||
publishes the total distance travelled by a robot. | ||
|
||
## Build | ||
|
||
Compile the sensor as follows: | ||
|
||
``` | ||
cd examples/custom_sensor | ||
mkdir build | ||
cd build | ||
cmake .. | ||
make | ||
``` | ||
|
||
This will generate a shared library with the sensor called `libodometer`. | ||
|
||
## Use | ||
|
||
This sensor can be used with Ignition Gazebo, or with any downstream | ||
application that uses the Ignition Sensors API. Listed here are two ways of | ||
testing this sensor, one with Gazebo and one with a custom program. | ||
|
||
### With a custom program | ||
|
||
The [loop_sensor](../loop_sensor) example can be used to load an SDF file with | ||
configuration for this sensor and run it in a loop. See that example's | ||
instructions. | ||
|
||
### With Ignition Gazebo | ||
|
||
The | ||
[custom_sensor_system](https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/custom_sensor_system) | ||
example can be used to load this sensor into Gazebo and update it during the | ||
simulation. | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,21 @@ | ||
cmake_minimum_required(VERSION 3.5 FATAL_ERROR) | ||
project(loop_sensor) | ||
|
||
find_package(ignition-sensors6 REQUIRED | ||
# Find built-in sensors | ||
COMPONENTS | ||
altimeter | ||
) | ||
|
||
# A simple example of how to find custom sensors | ||
add_subdirectory(../custom_sensor odometer) | ||
|
||
add_executable(${PROJECT_NAME} main.cc) | ||
target_link_libraries(${PROJECT_NAME} PUBLIC | ||
ignition-sensors6::ignition-sensors6 | ||
|
||
# Link to custom sensors | ||
odometer | ||
|
||
# Link to built-in sensors | ||
ignition-sensors6::altimeter) |
Oops, something went wrong.