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 441cc60 commit e45fdbb
Show file tree
Hide file tree
Showing 5 changed files with 22 additions and 22 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -88,12 +88,12 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
*
* \return array of size 3 with force values (x, y, z).
*/
std::array<double, 3> get_forces()
std::array<double, 3> get_forces() const
{
std::array<double, 3> forces{
{double_limits::quiet_NaN(), double_limits::quiet_NaN(), double_limits::quiet_NaN()}};
size_t interface_counter{0};
for (size_t i{0}; i < forces.size(); ++i)
for (auto i = 0u; i < forces.size(); ++i)
{
if (existing_axes_[i])
{
Expand All @@ -110,16 +110,16 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
*
* \return array of size 3 with torque values (x, y, z).
*/
std::array<double, 3> get_torques()
std::array<double, 3> get_torques() const
{
std::array<double, 3> torques{
{double_limits::quiet_NaN(), double_limits::quiet_NaN(), double_limits::quiet_NaN()}};
// find out how many force interfaces are being used
// torque interfaces will be found from the next index onward
auto torque_interface_counter{static_cast<size_t>(
std::count(existing_axes_.begin(), existing_axes_.begin() + forces_size_, true))};
auto torque_interface_counter = static_cast<size_t>(
std::count(existing_axes_.begin(), existing_axes_.begin() + forces_size_, true));

for (size_t i{0}; i < torques.size(); ++i)
for (auto i = 0u; i < torques.size(); ++i)
{
if (existing_axes_[i + forces_size_])
{
Expand All @@ -138,7 +138,7 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
*
* \return wrench message from values;
*/
bool get_values_as_message(geometry_msgs::msg::Wrench & message)
bool get_values_as_message(geometry_msgs::msg::Wrench & message) const
{
const auto [force_x, force_y, force_z] = get_forces();
const auto [torque_x, torque_y, torque_z] = get_torques();
Expand Down
14 changes: 7 additions & 7 deletions controller_interface/include/semantic_components/imu_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,10 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
*
* \return Array of size 4 with orientation quaternion (x,y,z,w).
*/
std::array<double, 4> get_orientation()
std::array<double, 4> get_orientation() const
{
std::array<double, 4> orientation;
for (std::size_t i{0}; i < orientation.size(); ++i)
for (auto i = 0u; i < orientation.size(); ++i)
{
orientation[i] = state_interfaces_[i].get().get_value();
}
Expand All @@ -64,11 +64,11 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
*
* \return array of size 3 with angular velocity values (x, y, z).
*/
std::array<double, 3> get_angular_velocity()
std::array<double, 3> get_angular_velocity() const
{
std::array<double, 3> angular_velocity;
const std::size_t interface_offset{4};
for (std::size_t i{0}; i < angular_velocity.size(); ++i)
for (auto i = 0u; i < angular_velocity.size(); ++i)
{
angular_velocity[i] = state_interfaces_[interface_offset + i].get().get_value();
}
Expand All @@ -81,11 +81,11 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
*
* \return array of size 3 with linear acceleration values (x, y, z).
*/
std::array<double, 3> get_linear_acceleration()
std::array<double, 3> get_linear_acceleration() const
{
std::array<double, 3> linear_acceleration;
const std::size_t interface_offset{7};
for (std::size_t i{0}; i < linear_acceleration.size(); ++i)
for (auto i = 0u; i < linear_acceleration.size(); ++i)
{
linear_acceleration[i] = state_interfaces_[interface_offset + i].get().get_value();
}
Expand All @@ -97,7 +97,7 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
* Constructs and return a IMU message from the current values.
* \return imu message from values;
*/
bool get_values_as_message(sensor_msgs::msg::Imu & message)
bool get_values_as_message(sensor_msgs::msg::Imu & message) const
{
const auto [orientation_x, orientation_y, orientation_z, orientation_w] = get_orientation();
const auto [angular_velocity_x, angular_velocity_y, angular_velocity_z] =
Expand Down
10 changes: 5 additions & 5 deletions controller_interface/include/semantic_components/pose_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
*
* \return Array of position coordinates.
*/
std::array<double, 3> get_position()
std::array<double, 3> get_position() const
{
std::array<double, 3> position;
for (std::size_t i{0}; i < position.size(); ++i)
for (auto i = 0u; i < position.size(); ++i)
{
position[i] = state_interfaces_[i].get().get_value();
}
Expand All @@ -62,11 +62,11 @@ class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
*
* \return Array of orientation coordinates in xyzw convention.
*/
std::array<double, 4> get_orientation()
std::array<double, 4> get_orientation() const
{
std::array<double, 4> orientation;
const std::size_t interface_offset{3};
for (std::size_t i{0}; i < orientation.size(); ++i)
for (auto i = 0u; i < orientation.size(); ++i)
{
orientation[i] = state_interfaces_[interface_offset + i].get().get_value();
}
Expand All @@ -77,7 +77,7 @@ class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
/**
* Fill a pose message with current position and orientation from the state interfaces.
*/
bool get_values_as_message(geometry_msgs::msg::Pose & message)
bool get_values_as_message(geometry_msgs::msg::Pose & message) const
{
const auto [position_x, position_y, position_z] = get_position();
const auto [orientation_x, orientation_y, orientation_z, orientation_w] = get_orientation();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,14 @@ class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
*
* \return value of the range in meters
*/
float get_range() { return state_interfaces_[0].get().get_value(); }
float get_range() const { return state_interfaces_[0].get().get_value(); }

/// Return Range message with range in meters
/**
* Constructs and return a Range message from the current values.
* \return Range message from values;
*/
bool get_values_as_message(sensor_msgs::msg::Range & message)
bool get_values_as_message(sensor_msgs::msg::Range & message) const
{
message.range = get_range();
return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class SemanticComponentInterface
state_interfaces_.reserve(interface_names.size());
}

explicit SemanticComponentInterface(const std::string & name, 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 e45fdbb

Please sign in to comment.