Skip to content

Commit

Permalink
Some renaming + update_statistics -> publish_statistics + agent tool …
Browse files Browse the repository at this point in the history
…docs + timeout reply (#94)

* agent_tool -> amlip_agent | ModelDataType -> ModelRequestDataType | ModelSolutionDataType -> ModelReplyDataType

Signed-off-by: Irene Bandera <[email protected]>

* Add comments

Signed-off-by: Irene Bandera <[email protected]>

* Uncrustify

Signed-off-by: Irene Bandera <[email protected]>

* Memory leaks

Signed-off-by: Irene Bandera <[email protected]>

* Add agent tool docu

Signed-off-by: Irene Bandera <[email protected]>

* Apply changes

Signed-off-by: Irene Bandera <[email protected]>

* Add copy_data parameter

Signed-off-by: Irene Bandera <[email protected]>

* Add timeout to get a reply

Signed-off-by: Irene Bandera <[email protected]>

* Uncrustify

Signed-off-by: Irene Bandera <[email protected]>

* Apply changes

Signed-off-by: Irene Bandera <[email protected]>

* Apply changes

Signed-off-by: Irene Bandera <[email protected]>

---------

Signed-off-by: Irene Bandera <[email protected]>
  • Loading branch information
irenebm authored Aug 7, 2023
1 parent 8a16e7b commit 5cfbf9e
Show file tree
Hide file tree
Showing 57 changed files with 1,031 additions and 388 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
#include <amlip_cpp/node/ParentNode.hpp>

#include <amlip_cpp/types/id/TaskId.hpp>
#include <amlip_cpp/types/model/ModelDataType.hpp>
#include <amlip_cpp/types/model/ModelSolutionDataType.hpp>
#include <amlip_cpp/types/model/ModelReplyDataType.hpp>
#include <amlip_cpp/types/model/ModelRequestDataType.hpp>
#include <amlip_cpp/types/model/ModelStatisticsDataType.hpp>


Expand All @@ -54,7 +54,7 @@ namespace node {
* @brief Object that listens to:
*
* - new ModelStatisticsDataType messages received from a \c ModelManagerSenderNode and executes a callback.
* - new ModelSolutionDataType messages received from a \c ModelManagerSenderNode and executes a callback.
* - new ModelReplyDataType messages received from a \c ModelManagerSenderNode and executes a callback.
*
* This class is supposed to be implemented by a User and be given to a \c ModelManagerReceiverNode in order to process
* the messages received from other Nodes in the network.
Expand All @@ -75,12 +75,12 @@ class ModelListener
const types::ModelStatisticsDataType statistics) = 0;

/**
* @brief Method that will be called with each ModelSolutionDataType message received
* @brief Method that will be called with each ModelReplyDataType message received
*
* @param model new ModelSolutionDataType message received.
* @param model new ModelReplyDataType message received.
*/
virtual bool model_received (
const types::ModelSolutionDataType model) = 0;
const types::ModelReplyDataType model) = 0;
};

/**
Expand All @@ -101,7 +101,7 @@ class ModelManagerReceiverNode : public ParentNode
*/
AMLIP_CPP_DllAPI ModelManagerReceiverNode(
types::AmlipIdDataType id,
types::ModelDataType& data,
types::ModelRequestDataType& data,
uint32_t domain_id);

/**
Expand All @@ -112,7 +112,7 @@ class ModelManagerReceiverNode : public ParentNode
*/
AMLIP_CPP_DllAPI ModelManagerReceiverNode(
types::AmlipIdDataType id,
types::ModelDataType& data);
types::ModelRequestDataType& data);

/**
* @brief Construct a new ModelManagerReceiverNode Node object.
Expand All @@ -123,7 +123,7 @@ class ModelManagerReceiverNode : public ParentNode
*/
AMLIP_CPP_DllAPI ModelManagerReceiverNode(
const char* name,
types::ModelDataType& data,
types::ModelRequestDataType& data,
uint32_t domain_id);

/**
Expand All @@ -134,7 +134,7 @@ class ModelManagerReceiverNode : public ParentNode
*/
AMLIP_CPP_DllAPI ModelManagerReceiverNode(
const char* name,
types::ModelDataType& data);
types::ModelRequestDataType& data);

/**
* @brief Destroy the ModelManagerReceiverNode Node object
Expand Down Expand Up @@ -190,13 +190,16 @@ class ModelManagerReceiverNode : public ParentNode
*
* This is created from DDS Participant in ParentNode, and its destruction is handled by ParentNode.
*/
std::shared_ptr<dds::RPCClient<types::ModelDataType, types::ModelSolutionDataType>> model_receiver_;
std::shared_ptr<dds::RPCClient<types::ModelRequestDataType, types::ModelReplyDataType>> model_receiver_;

//! Whether the Node is currently open to receive data or it is stopped.
std::atomic<bool> running_;

//! Data to request to ModelManagerSenderNode.
types::ModelDataType data_;
types::ModelRequestDataType data_;

//! Maximum wait reply in milliseconds (0 = no wait)
static const uint32_t REPLY_TIMEOUT_; // 2500
};

} /* namespace node */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
#include <amlip_cpp/node/ParentNode.hpp>

#include <amlip_cpp/types/id/TaskId.hpp>
#include <amlip_cpp/types/model/ModelDataType.hpp>
#include <amlip_cpp/types/model/ModelSolutionDataType.hpp>
#include <amlip_cpp/types/model/ModelReplyDataType.hpp>
#include <amlip_cpp/types/model/ModelRequestDataType.hpp>
#include <amlip_cpp/types/model/ModelStatisticsDataType.hpp>


Expand All @@ -53,7 +53,7 @@ namespace node {
/**
* @brief Object that listens to:
*
* - new ModelDataType messages received from a \c ModelManagerReceiverNode and executes a callback.
* - new ModelRequestDataType messages received from a \c ModelManagerReceiverNode and executes a callback.
*
* This class is supposed to be implemented by a User and be given to a \c ModelManagerSenderNode in order to process
* the messages received from other Nodes in the network.
Expand All @@ -67,12 +67,12 @@ class ModelReplier
virtual ~ModelReplier() = default;

/**
* @brief Method that will be called with each ModelSolutionDataType message received to calculate an answer.
* @brief Method that will be called with each ModelReplyDataType message received to calculate an answer.
*
* @param data new ModelDataType message received.
* @param data new ModelRequestDataType message received.
*/
virtual types::ModelSolutionDataType fetch_model (
const types::ModelDataType data) = 0;
virtual types::ModelReplyDataType fetch_model (
const types::ModelRequestDataType data) = 0;
};

/**
Expand Down Expand Up @@ -109,34 +109,42 @@ class ModelManagerSenderNode : public ParentNode
AMLIP_CPP_DllAPI ~ModelManagerSenderNode();

/**
* @brief This function copies the values in member \c statistics_ and publishes them
* @brief This function copies the values into a ModelStatisticsDataType object and publishes them
*
* @param name New value to be copied in member id \c statistics_.name_
* @param data New value to be copied in member id \c statistics_.data_
* @param size New value to be copied in member id \c statistics_.data_size_
* @param name New value to be copied in member \c name_
* @param data New value to be copied in member \c data_
* @param size New value to be copied in member \c data_size_
* @param copy_data
*/
void update_statistics(
void publish_statistics(
const std::string& name,
void* data,
const uint32_t size);
const uint32_t size,
bool copy_data = true);

/**
* @brief This function copies the values in member \c statistics_ and publishes them
* @brief This function copies the values into a ModelStatisticsDataType object and publishes them
*
* @param name New value to be copied in member id \c statistics_.name_
* @param data New value to be copied in member id \c statistics_.data_
* @param name New value to be copied in member \c name_
* @param data New value to be copied in member \c data_
* @param copy_data
*/
void update_statistics(
void publish_statistics(
const std::string& name,
const std::string& data);
const std::vector<types::ByteType>& data,
bool copy_data = true);

/**
* @brief This function gets the value of member \c statistics_ as ModelStatisticsDataType
* @brief This function copies the values into a ModelStatisticsDataType object and publishes them
*
* @return Value of member \c statistics_ as ModelStatisticsDataType
* @param name New value to be copied in member \c name_
* @param data New value to be copied in member \c data_
* @param copy_data
*/
types::ModelStatisticsDataType statistics();

void publish_statistics(
const std::string& name,
const std::string& data,
bool copy_data = true);

/**
* @brief Process model replies
Expand Down Expand Up @@ -185,13 +193,11 @@ class ModelManagerSenderNode : public ParentNode
*
* This is created from DDS Participant in ParentNode, and its destruction is handled by ParentNode.
*/
std::shared_ptr<dds::RPCServer<types::ModelDataType, types::ModelSolutionDataType>> model_sender_;
std::shared_ptr<dds::RPCServer<types::ModelRequestDataType, types::ModelReplyDataType>> model_sender_;

//! Whether the Node is currently open to receive data or it is stopped.
std::atomic<bool> running_;

//! Statistical data from models.
types::ModelStatisticsDataType statistics_;
};

} /* namespace node */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@
// limitations under the License.

/*!
* @file ModelDataType.hpp
* @file ModelReplyDataType.hpp
*/

#ifndef AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELDATATYPE_HPP
#define AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELDATATYPE_HPP
#ifndef AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELREPLYDATATYPE_HPP
#define AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELREPLYDATATYPE_HPP

#include <string>
#include <vector>
Expand All @@ -28,10 +28,10 @@ namespace eprosima {
namespace amlip {
namespace types {

using ModelDataType = GenericDataType;
using ModelReplyDataType = GenericDataType;

} /* namespace types */
} /* namespace amlip */
} /* namespace eprosima */

#endif // AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELDATATYPE_HPP
#endif // AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELREPLYDATATYPE_HPP
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@
// limitations under the License.

/*!
* @file ModelSolutionDataType.hpp
* @file ModelRequestDataType.hpp
*/

#ifndef AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELSOLUTIONDATATYPE_HPP
#define AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELSOLUTIONDATATYPE_HPP
#ifndef AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELREQUESTDATATYPE_HPP
#define AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELREQUESTDATATYPE_HPP

#include <string>
#include <vector>
Expand All @@ -28,10 +28,10 @@ namespace eprosima {
namespace amlip {
namespace types {

using ModelSolutionDataType = GenericDataType;
using ModelRequestDataType = GenericDataType;

} /* namespace types */
} /* namespace amlip */
} /* namespace eprosima */

#endif // AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELSOLUTIONDATATYPE_HPP
#endif // AMLIPCPP__SRC_CPP_TYPES_MODEL_MODELREQUESTDATATYPE_HPP
62 changes: 43 additions & 19 deletions amlip_cpp/include/amlip_cpp/types/model/ModelStatisticsDataType.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#include <string>
#include <vector>

#include <amlip_cpp/types/InterfaceDataType.hpp>
#include <amlip_cpp/types/id/AmlipIdDataType.hpp>
#include <amlip_cpp/types/InterfaceDataType.hpp>

namespace eprosima {
namespace fastcdr {
Expand All @@ -49,16 +49,53 @@ class ModelStatisticsDataType : public InterfaceDataType

/*!
* @brief Constructor with name.
* @param name New value to be copied in member id \c name_
*/
AMLIP_CPP_DllAPI ModelStatisticsDataType(
const std::string& name);

/*!
* @brief Constructor with name given in char*.
* @param name New value to be copied in member id \c name_
*/
AMLIP_CPP_DllAPI ModelStatisticsDataType(
const char* name);

/*!
* @brief Constructor with name, data given in void* and data size.
* @param name New value to be copied in member id \c name_
* @param data New value to be copied in member id \c data_
* @param size New value to be copied in member id \c data_size_
* @param copy_data
*/
AMLIP_CPP_DllAPI ModelStatisticsDataType(
const std::string& name,
void* data,
const uint32_t size,
bool copy_data = true);

/*!
* @brief Constructor with name and data given in std::vector<uint8_t>.
* @param name New value to be copied in member id \c name_
* @param bytes New value to be copied in member id \c data_
* @param copy_data
*/
AMLIP_CPP_DllAPI ModelStatisticsDataType(
const std::string& name,
const std::vector<ByteType>& bytes,
bool copy_data = true);

/*!
* @brief Constructor with name and data.
* @param name New value to be copied in member id \c name_
* @param bytes New value to be copied in member id \c data_
* @param copy_data
*/
AMLIP_CPP_DllAPI ModelStatisticsDataType(
const std::string& name,
const std::string& bytes,
bool copy_data = true);

/*!
* @brief Default destructor.
*/
Expand Down Expand Up @@ -145,27 +182,14 @@ class ModelStatisticsDataType : public InterfaceDataType
AMLIP_CPP_DllAPI void* data() const;

/*!
* @brief This function copies the value in member \c data_
* @param bytes New value to be copied in member id \c data_
*/
AMLIP_CPP_DllAPI void data(
const std::vector<ByteType>& bytes);

/*!
* @brief This function copies the value in member \c data_
* @param bytes New value to be copied in member id \c data_
* @brief Return value of attribute \c data_ in std::string
*/
AMLIP_CPP_DllAPI void data(
const std::string& bytes);
AMLIP_CPP_DllAPI std::string to_string() const noexcept;

/*!
* @brief This function copies the value in member \c data_
* @param data New value to be copied in member id \c data_
* @param size New value to be copied in member id \c data_size_
* @brief Return value of attribute \c data_ in std::vector<uint8_t>
*/
AMLIP_CPP_DllAPI void data(
void* data,
const uint32_t size);
AMLIP_CPP_DllAPI std::vector<ByteType> to_vector() const noexcept;

/*!
* @brief Return value of attribute \c data_size_
Expand Down Expand Up @@ -271,7 +295,7 @@ class ModelStatisticsDataType : public InterfaceDataType
};

//! \c ModelStatisticsDataType to stream serializator
AMLIP_CPP_DllAPI std::ostream& operator <<(
std::ostream& operator <<(
std::ostream& os,
const ModelStatisticsDataType& id);

Expand Down
8 changes: 7 additions & 1 deletion amlip_cpp/src/cpp/dds/rpc/RPCClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,9 @@
#include <dds/DirectWriter.hpp>
#include <dds/TargetedReader.hpp>

#include <types/rpc/RpcRequestDataType.hpp>
#include <types/rpc/RpcReplyDataType.hpp>
#include <types/rpc/RpcRequestDataType.hpp>

#include <amlip_cpp/types/id/TaskId.hpp>

namespace eprosima {
Expand Down Expand Up @@ -107,6 +108,11 @@ class RPCClient
std::string topic_;

std::atomic<types::TaskId> last_task_id_used_;

template <typename D, typename S>
friend std::ostream& operator <<(
std::ostream&,
const RPCClient<D, S>& );
};

//! \c RPCClient to stream serializator
Expand Down
Loading

0 comments on commit 5cfbf9e

Please sign in to comment.