Skip to content

Commit dd047df

Browse files
committed
switched from handling the data package as a unique pointer to a plain reference
1 parent 9acb35e commit dd047df

File tree

4 files changed

+11
-11
lines changed

4 files changed

+11
-11
lines changed

Diff for: ur_robot_driver/include/ur_robot_driver/ros/data_field_publisher.h

+5-5
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ class DataFieldPublisher
5151
*
5252
* \returns True if the realtime publisher could publish the data.
5353
*/
54-
virtual bool publish(const std::unique_ptr<DataPackage>& data_package) = 0;
54+
virtual bool publish(const DataPackage& data_package) = 0;
5555

5656
/*!
5757
* \brief Creates a DataFieldPublisher object based on a given data field.
@@ -93,9 +93,9 @@ class DirectDataPublisher : public DataFieldPublisher
9393
*
9494
* \returns True if the realtime publisher could publish the data.
9595
*/
96-
virtual bool publish(const std::unique_ptr<DataPackage>& data_package)
96+
virtual bool publish(const DataPackage& data_package)
9797
{
98-
if (data_package->getData(data_field_identifier_, data_))
98+
if (data_package.getData(data_field_identifier_, data_))
9999
{
100100
if (pub_)
101101
{
@@ -145,9 +145,9 @@ class ArrayDataPublisher : public DataFieldPublisher
145145
*
146146
* \returns True if the realtime publisher could publish the data.
147147
*/
148-
virtual bool publish(const std::unique_ptr<DataPackage>& data_package)
148+
virtual bool publish(const DataPackage& data_package)
149149
{
150-
if (data_package->getData(data_field_identifier_, data_))
150+
if (data_package.getData(data_field_identifier_, data_))
151151
{
152152
if (pub_)
153153
{

Diff for: ur_robot_driver/include/ur_robot_driver/ros/data_package_publisher.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,12 +58,12 @@ class DataPackagePublisher
5858
}
5959
}
6060

61-
void publishData(const std::unique_ptr<DataPackage>& data_package)
6261
/*!
6362
* \brief Publishes all relevant data fields of a given data package.
6463
*
6564
* \param data_package The data package to publish
6665
*/
66+
void publishData(const DataPackage& data_package)
6767
{
6868
for (auto const& i : publishers_)
6969
{

Diff for: ur_robot_driver/include/ur_robot_driver/rtde/data_package.h

+4-4
Original file line numberDiff line numberDiff line change
@@ -127,11 +127,11 @@ class DataPackage : public RTDEPackage
127127
* \returns True on success, false if the field cannot be found inside the package.
128128
*/
129129
template <typename T>
130-
bool getData(const std::string& name, T& val)
130+
bool getData(const std::string& name, T& val) const
131131
{
132132
if (data_.find(name) != data_.end())
133133
{
134-
val = boost::strict_get<T>(data_[name]);
134+
val = boost::strict_get<T>(data_.at(name));
135135
}
136136
else
137137
{
@@ -152,13 +152,13 @@ class DataPackage : public RTDEPackage
152152
* \returns True on success, false if the field cannot be found inside the package.
153153
*/
154154
template <typename T, size_t N>
155-
bool getData(const std::string& name, std::bitset<N>& val)
155+
bool getData(const std::string& name, std::bitset<N>& val) const
156156
{
157157
static_assert(sizeof(T) * 8 >= N, "Bitset is too large for underlying variable");
158158

159159
if (data_.find(name) != data_.end())
160160
{
161-
val = std::bitset<N>(boost::strict_get<T>(data_[name]));
161+
val = std::bitset<N>(boost::strict_get<T>(data_.at(name)));
162162
}
163163
else
164164
{

Diff for: ur_robot_driver/src/ros/hardware_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -415,7 +415,7 @@ void HardwareInterface::read(const ros::Time& time, const ros::Duration& period)
415415
publishPose();
416416
publishRobotAndSafetyMode();
417417

418-
rtde_data_pub_->publishData(data_pkg);
418+
rtde_data_pub_->publishData(*data_pkg);
419419

420420
// pausing state follows runtime state when pausing
421421
if (runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSED))

0 commit comments

Comments
 (0)