Skip to content

Commit

Permalink
Add fixes after review
Browse files Browse the repository at this point in the history
  • Loading branch information
Wiktor-99 committed Dec 19, 2024
1 parent e45fdbb commit c783fcc
Show file tree
Hide file tree
Showing 5 changed files with 34 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,16 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
{
public:
/// Constructor for "standard" 6D FTS
explicit ForceTorqueSensor(const std::string & name) : SemanticComponentInterface{name,
// If 6D FTS use standard names
{ {name + "/" + "force.x"},
{name + "/" + "force.y"},
{name + "/" + "force.z"},
{name + "/" + "torque.x"},
{name + "/" + "torque.y"},
{name + "/" + "torque.z"} }},
explicit ForceTorqueSensor(const std::string & name)
: SemanticComponentInterface(
name,
// If 6D FTS use standard names
{{name + "/" + "force.x"},
{name + "/" + "force.y"},
{name + "/" + "force.z"},
{name + "/" + "torque.x"},
{name + "/" + "torque.y"},
{name + "/" + "torque.z"}}),
existing_axes_{{true, true, true, true, true, true}}
{
}
Expand Down
23 changes: 11 additions & 12 deletions controller_interface/include/semantic_components/imu_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,18 +28,17 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
{
public:
explicit IMUSensor(const std::string & name)
: SemanticComponentInterface{
name,
{{name + "/" + "orientation.x"},
{name + "/" + "orientation.y"},
{name + "/" + "orientation.z"},
{name + "/" + "orientation.w"},
{name + "/" + "angular_velocity.x"},
{name + "/" + "angular_velocity.y"},
{name + "/" + "angular_velocity.z"},
{name + "/" + "linear_acceleration.x"},
{name + "/" + "linear_acceleration.y"},
{name + "/" + "linear_acceleration.z"}}}
: SemanticComponentInterface(
name, {{name + "/" + "orientation.x"},
{name + "/" + "orientation.y"},
{name + "/" + "orientation.z"},
{name + "/" + "orientation.w"},
{name + "/" + "angular_velocity.x"},
{name + "/" + "angular_velocity.y"},
{name + "/" + "angular_velocity.z"},
{name + "/" + "linear_acceleration.x"},
{name + "/" + "linear_acceleration.y"},
{name + "/" + "linear_acceleration.z"}})
{
}
/// Return orientation.
Expand Down
17 changes: 8 additions & 9 deletions controller_interface/include/semantic_components/pose_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,14 @@ class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
public:
/// Constructor for a standard pose sensor with interface names set based on sensor name.
explicit PoseSensor(const std::string & name)
: SemanticComponentInterface{
name,
{{name + '/' + "position.x"},
{name + '/' + "position.y"},
{name + '/' + "position.z"},
{name + '/' + "orientation.x"},
{name + '/' + "orientation.y"},
{name + '/' + "orientation.z"},
{name + '/' + "orientation.w"}}}
: SemanticComponentInterface(
name, {{name + '/' + "position.x"},
{name + '/' + "position.y"},
{name + '/' + "position.z"},
{name + '/' + "orientation.x"},
{name + '/' + "orientation.y"},
{name + '/' + "orientation.z"},
{name + '/' + "orientation.w"}})
{
}
/// Update and return position.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
{
public:
explicit RangeSensor(const std::string & name)
: SemanticComponentInterface{name, {{name + "/" + "range"}}}
: SemanticComponentInterface(name, {name + "/" + "range"})
{
}
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,14 @@ template <typename MessageReturnType>
class SemanticComponentInterface
{
public:
SemanticComponentInterface(const std::string & name, std::vector<std::string> interface_names)
: name_{name}, interface_names_{interface_names}
SemanticComponentInterface(
const std::string & name, const std::vector<std::string> & interface_names)
: name_(name), interface_names_(interface_names)
{
state_interfaces_.reserve(interface_names.size());
}

explicit SemanticComponentInterface(const std::string & name, std::size_t size = 0) : name_{name}
explicit SemanticComponentInterface(const std::string & name, std::size_t size = 0) : name_(name)
{
interface_names_.reserve(size);
state_interfaces_.reserve(size);
Expand Down

0 comments on commit c783fcc

Please sign in to comment.