Skip to content
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
20 changes: 14 additions & 6 deletions hardware_interface/include/hardware_interface/components/joint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class Joint
* return_type::ERROR otherwise.
*/
HARDWARE_INTERFACE_PUBLIC
virtual
return_type configure(const ComponentInfo & joint_info);

/**
Expand All @@ -58,6 +59,7 @@ class Joint
* \return string list with command interfaces.
*/
HARDWARE_INTERFACE_PUBLIC
virtual
std::vector<std::string> get_command_interfaces() const;

/**
Expand All @@ -66,6 +68,7 @@ class Joint
* \return string list with state interfaces.
*/
HARDWARE_INTERFACE_PUBLIC
virtual
std::vector<std::string> get_state_interfaces() const;

/**
Expand All @@ -82,9 +85,9 @@ class Joint
* is empty; return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type get_command(
std::vector<double> & command,
const std::vector<std::string> & interfaces) const;
std::vector<double> & command, const std::vector<std::string> & interfaces) const;

/**
* \brief Get complete command list for the joint. This function is used by the hardware to get
Expand All @@ -95,6 +98,7 @@ class Joint
* \return return_type::OK always.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type get_command(std::vector<double> & command) const;

/**
Expand All @@ -114,9 +118,9 @@ class Joint
* (see: https://github.com/ros-controls/ros2_control/issues/129)
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type set_command(
const std::vector<double> & command,
const std::vector<std::string> & interfaces);
const std::vector<double> & command, const std::vector<std::string> & interfaces);

/**
* \brief Get complete state list from the joint. This function is used by the hardware to get
Expand All @@ -129,6 +133,7 @@ class Joint
* of limits; return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type set_command(const std::vector<double> & command);

/**
Expand All @@ -144,6 +149,7 @@ class Joint
* is empty; return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type get_state(
std::vector<double> & state,
const std::vector<std::string> & interfaces) const;
Expand All @@ -157,6 +163,7 @@ class Joint
* \return return_type::OK always.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type get_state(std::vector<double> & state) const;

/**
Expand All @@ -171,9 +178,9 @@ class Joint
* defined for the joint; return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type set_state(
const std::vector<double> & state,
const std::vector<std::string> & interfaces);
const std::vector<double> & state, const std::vector<std::string> & interfaces);

/**
* \brief Set complete state list from the joint.This function is used by the hardware to set its
Expand All @@ -185,6 +192,7 @@ class Joint
* joint's state interfaces, return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type set_state(const std::vector<double> & state);

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class Sensor
* return_type::ERROR otherwise.
*/
HARDWARE_INTERFACE_PUBLIC
virtual
return_type configure(const ComponentInfo & joint_info);

/**
Expand All @@ -58,7 +59,8 @@ class Sensor
* \return string list with state interfaces.
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<std::string> get_state_interfaces();
virtual
std::vector<std::string> get_state_interfaces() const;

/**
* \brief Get state list from the sensor. This function is used by the controller to get the
Expand All @@ -73,9 +75,9 @@ class Sensor
* is empty; return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type get_state(
std::vector<double> & state,
const std::vector<std::string> & interfaces) const;
std::vector<double> & state, const std::vector<std::string> & interfaces) const;

/**
* \brief Get complete state list from the sensor. This function is used by the controller to get
Expand All @@ -86,6 +88,7 @@ class Sensor
* \return return_type::OK always.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type get_state(std::vector<double> & state) const;

/**
Expand All @@ -100,9 +103,9 @@ class Sensor
* defined for the sensor; return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type set_state(
const std::vector<double> & state,
const std::vector<std::string> & interfaces);
const std::vector<double> & state, const std::vector<std::string> & interfaces);

/**
* \brief Set complete state list from the sensor.This function is used by the hardware to set its
Expand All @@ -114,6 +117,7 @@ class Sensor
* sensor's state interfaces, return_type::OK otherwise.
*/
HARDWARE_INTERFACE_EXPORT
virtual
return_type set_state(const std::vector<double> & state);

protected:
Expand Down
4 changes: 1 addition & 3 deletions hardware_interface/src/components/joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include <vector>

#include "hardware_interface/components/joint.hpp"

#include "hardware_interface/components/component_info.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"

Expand Down Expand Up @@ -61,8 +60,7 @@ return_type Joint::get_command(std::vector<double> & command) const
}

return_type Joint::set_command(
const std::vector<double> & command,
const std::vector<std::string> & interfaces)
const std::vector<double> & command, const std::vector<std::string> & interfaces)
{
return set_internal_values(command, interfaces, info_.command_interfaces, commands_);
}
Expand Down
3 changes: 1 addition & 2 deletions hardware_interface/src/components/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include <vector>

#include "hardware_interface/components/sensor.hpp"

#include "hardware_interface/components/component_info.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"

Expand All @@ -36,7 +35,7 @@ return_type Sensor::configure(const ComponentInfo & joint_info)
return return_type::OK;
}

std::vector<std::string> Sensor::get_state_interfaces()
std::vector<std::string> Sensor::get_state_interfaces() const
{
return info_.state_interfaces;
}
Expand Down