Add dynamic configuration features and test cases (#12)
* Add dynamic configuration feature. 1. Add a test sample as dynamic configuration test app 2. Add dynamic configuration operation for the device twin changes 3. Update the exsting telemetry reporting logic, subscribe the topics in real time. 4. Update the logging with ROS commands. * Add test case for dynamic configuration * Update readme * Update IOT hub connection strings with placeholder * Fix build issues on Linux. * Minor update on the readme content * Remove \r\n from ROS logging API * Update dynamic_tutorials package infomation * Update test.launch for parameterization * Minor update on readme files * Fix the build break on linux. * Update processing logic for ros_dynamic_configurations, remove the global variable to make the logic clear.
This commit is contained in:
Родитель
9f5cdca60f
Коммит
0c790978f3
|
@ -0,0 +1,11 @@
|
|||
# Samples for the Azure IoT Hub connector
|
||||
|
||||
These samples demostrate how to use the various features of Microsoft Azure IoT Hub service to relay telemetry messages or dynamic reconfiguration commands in ROS nodes.
|
||||
|
||||
## List of samples
|
||||
|
||||
* [IOT Hub connector sample in C++](./roscpp_azure_iothub/)
|
||||
|
||||
* [IOT Hub connector sample in Python](./rospy_azure_iothub/)
|
||||
|
||||
* [Dynamic reconfiguration sample](./dynamic_tutorials/)
|
|
@ -0,0 +1,40 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(dynamic_tutorials)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
dynamic_reconfigure
|
||||
roscpp
|
||||
)
|
||||
|
||||
generate_dynamic_reconfigure_options(
|
||||
cfg/tutorials.cfg
|
||||
)
|
||||
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
include_directories(
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
|
||||
add_executable(${PROJECT_NAME}_node src/server.cpp)
|
||||
|
||||
add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}_node
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
install(TARGETS ${PROJECT_NAME}_node
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
|
@ -0,0 +1,13 @@
|
|||
#!/usr/bin/env python
|
||||
PACKAGE = "dynamic_tutorials"
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||
|
||||
gen = ParameterGenerator()
|
||||
|
||||
gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
|
||||
gen.add("double_param", double_t, 0, "A double parameter", .5, 0, 1)
|
||||
gen.add("str_param", str_t, 0, "A string parameter", "Hello World")
|
||||
gen.add("bool_param", bool_t, 0, "A Boolean parameter", True)
|
||||
|
||||
exit(gen.generate(PACKAGE, "dynamic_tutorials", "tutorials"))
|
|
@ -0,0 +1,15 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>dynamic_tutorials</name>
|
||||
<version>1.0.0</version>
|
||||
<description>This sample package demostrates how to set up up Dynamic Reconfigure for a ROS node.</description>
|
||||
<maintainer email="baoxij@microsoft.com">Baoxi Jia</maintainer>
|
||||
<license>MIT</license>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>dynamic_reconfigure</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_export_depend>dynamic_reconfigure</build_export_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<exec_depend>dynamic_reconfigure</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
</package>
|
|
@ -0,0 +1,26 @@
|
|||
#include <ros/ros.h>
|
||||
|
||||
#include <dynamic_reconfigure/server.h>
|
||||
#include <dynamic_tutorials/tutorialsConfig.h>
|
||||
|
||||
void callback(dynamic_tutorials::tutorialsConfig &config, uint32_t level) {
|
||||
ROS_INFO("Reconfigure Request: %d %f %s %s",
|
||||
config.int_param, config.double_param,
|
||||
config.str_param.c_str(),
|
||||
config.bool_param?"True":"False");
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "dynamic_tutorials_node");
|
||||
|
||||
dynamic_reconfigure::Server<dynamic_tutorials::tutorialsConfig> server;
|
||||
dynamic_reconfigure::Server<dynamic_tutorials::tutorialsConfig>::CallbackType f;
|
||||
|
||||
f = boost::bind(&callback, _1, _2);
|
||||
server.setCallback(f);
|
||||
|
||||
ROS_INFO("Spinning node");
|
||||
ros::spin();
|
||||
return 0;
|
||||
}
|
|
@ -13,12 +13,14 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
std_msgs
|
||||
topic_tools
|
||||
ros_type_introspection
|
||||
dynamic_reconfigure
|
||||
)
|
||||
|
||||
if (WIN32)
|
||||
find_package(azure_c_shared_utility REQUIRED)
|
||||
find_package(azure_iot_sdks REQUIRED)
|
||||
find_package(umqtt REQUIRED)
|
||||
find_package(uamqp REQUIRED)
|
||||
else (WIN32)
|
||||
set(IOTHUB_CLIENT_INCLUDES ".." "/usr/include/azureiot" "/usr/include/azureiot/inc" "./parson")
|
||||
add_library(parson STATIC
|
||||
|
@ -86,4 +88,16 @@ install(TARGETS ${PROJECT_NAME}_node
|
|||
|
||||
install(DIRECTORY launch/
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
|
||||
)
|
||||
)
|
||||
|
||||
#############
|
||||
## Test ##
|
||||
#############
|
||||
|
||||
if(WIN32)
|
||||
if(CATKIN_ENABLE_TESTING)
|
||||
find_package(rostest REQUIRED)
|
||||
add_rostest_gtest(${PROJECT_NAME}_testnode test/testiothub.launch test/testiothub.cpp)
|
||||
target_link_libraries(${PROJECT_NAME}_testnode iothub_service_client ${catkin_LIBRARIES} )
|
||||
endif()
|
||||
endif()
|
|
@ -23,7 +23,7 @@ Here is an example how to build it for ROS on Windows.
|
|||
> pushd src
|
||||
> git clone https://github.com/ms-iot/abseil-cpp -b init_windows
|
||||
> git clone https://github.com/ms-iot/ros_type_introspection -b init_windows
|
||||
> git clone https://github.com/Microsoft/ros_azure_iothub
|
||||
> git clone --recursive https://github.com/Microsoft/ros_azure_iothub
|
||||
> popd
|
||||
|
||||
> :: install system dependencies
|
||||
|
@ -48,7 +48,7 @@ $ catkin_init_workspace src
|
|||
|
||||
$ # checkout required ROS package sources
|
||||
$ pushd src
|
||||
$ git clone https://github.com/Microsoft/ros_azure_iothub
|
||||
$ git clone --recursive https://github.com/Microsoft/ros_azure_iothub
|
||||
$ popd
|
||||
|
||||
$ # install system dependencies
|
||||
|
@ -61,11 +61,12 @@ $ sudo apt-get update
|
|||
$ sudo apt-get install -y azure-iot-sdk-c-dev
|
||||
|
||||
$ # build it and source install environment
|
||||
$ chmod a+x src/ros_azure_iothub/dynamic_tutorials/cfg/tutorials.cfg
|
||||
$ catkin_make install
|
||||
$ source /install/setup.bash
|
||||
```
|
||||
|
||||
# Deployment (IoT Hub)
|
||||
# Deployment (IoT Hub for telemetry reporting)
|
||||
Device twins are JSON documents that store device state information including metadata, configurations, and conditions. Azure IoT Hub maintains a device twin for each device that you connect to IoT Hub. And we are using `desired` properties as a channel to ask our ROS node what ROS topics to report.
|
||||
|
||||
Here is a JSON example to report `/rosout`:
|
||||
|
@ -91,6 +92,49 @@ And add the `ros_relays` block to the device twin which you are about to connect
|
|||
az iot hub monitor-events --hub-name <YourIoTHubName> --output table
|
||||
```
|
||||
|
||||
# Deployment (IoT Hub for dynamic configuration)
|
||||
[Dynamic Reconfiguration](http://wiki.ros.org/dynamic_reconfigure) provides a way to change the node parameters during runtime without restarting the node.
|
||||
Similar as the telemetry reporting, we are using the device twin `desired` properties as a channel to ask our ROS node what dynamic parameters to reconfigure.
|
||||
|
||||
Here is a JSON example to reconfigure the parameters of `/dynamic_tutorials_node` with the new value:
|
||||
```
|
||||
{
|
||||
"deviceId": "devA",
|
||||
...
|
||||
"properties": {
|
||||
"desired": {
|
||||
"ros_dynamic_configurations": {
|
||||
"0": {
|
||||
"node": "/dynamic_tutorials_node",
|
||||
"param": "str_param",
|
||||
"type": "string"
|
||||
"value": "HelloWorld!",
|
||||
},
|
||||
"1": {
|
||||
"node": "/dynamic_tutorials_node",
|
||||
"param": "int_param",
|
||||
"type": "int"
|
||||
"value": "33",
|
||||
},
|
||||
"2": {
|
||||
"node": "/dynamic_tutorials_node",
|
||||
"param": "double_param",
|
||||
"type": "double"
|
||||
"value": "0.55",
|
||||
},
|
||||
"3": {
|
||||
"node": "/dynamic_tutorials_node",
|
||||
"param": "bool_param",
|
||||
"type": "bool",
|
||||
"value": "1"
|
||||
}
|
||||
...
|
||||
},
|
||||
...
|
||||
}
|
||||
}
|
||||
```
|
||||
Currently 4 types of parameters can be dynamically reconfigured, they are "string", "int", "double" and "bool".
|
||||
|
||||
# Deployment (Client side)
|
||||
This node can be run using `roslaunch` (replacing the value for `connection_string` with the value given by Azure IoT Hub):
|
||||
|
@ -100,7 +144,7 @@ roslaunch roscpp_azure_iothub sample.launch connection_string:="HostName=sample.
|
|||
|
||||
This value can also be set in the ROS Parameter Server at `/roscpp_azure_iothub_node/connection_string`.
|
||||
|
||||
Now you can run some other ROS scenarios and see the `/rosout` being reported back to IoT Hub.
|
||||
Now you can run some other ROS scenarios and see the `/rosout` being reported back to IoT Hub or the node parameters being dynamically reconfigured.
|
||||
|
||||
# Contributing
|
||||
|
||||
|
|
|
@ -19,4 +19,5 @@
|
|||
<depend>topic_tools</depend>
|
||||
<depend>ros_type_introspection</depend>
|
||||
<depend>libazure-iot-sdk-c</depend>
|
||||
<test_depend>rosunit</test_depend>
|
||||
</package>
|
||||
|
|
|
@ -5,28 +5,35 @@
|
|||
#include <inttypes.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <thread> // std::thread
|
||||
#include <mutex> // std::mutex, std::unique_lock
|
||||
#include <condition_variable> // std::condition_variable
|
||||
// Azure IoT Hub
|
||||
#ifdef _WIN32
|
||||
#include <azure_c_shared_utility/macro_utils.h>
|
||||
#else
|
||||
#include <azure_macro_utils/macro_utils.h>
|
||||
#endif
|
||||
|
||||
//Azure IoT Hub
|
||||
#include "azure_c_shared_utility/macro_utils.h"
|
||||
#include "azure_c_shared_utility/threadapi.h"
|
||||
#include "azure_c_shared_utility/platform.h"
|
||||
#include "iothub_device_client.h"
|
||||
#include "iothub_client_options.h"
|
||||
#include "iothub.h"
|
||||
#include "iothub_message.h"
|
||||
#include "parson.h"
|
||||
#include "iothubtransportmqtt.h"
|
||||
#include <azure_c_shared_utility/threadapi.h>
|
||||
#include <azure_c_shared_utility/platform.h>
|
||||
#include <iothub_device_client.h>
|
||||
#include <iothub_client_options.h>
|
||||
#include <iothub.h>
|
||||
#include <iothub_message.h>
|
||||
#include <parson.h>
|
||||
#include <iothubtransportmqtt.h>
|
||||
|
||||
//ROS Introspection
|
||||
#include "ros_type_introspection/ros_introspection.hpp"
|
||||
// ROS Introspection
|
||||
#include <ros_type_introspection/ros_introspection.hpp>
|
||||
#include <ros/ros.h>
|
||||
#include <topic_tools/shape_shifter.h>
|
||||
|
||||
using namespace RosIntrospection;
|
||||
|
||||
// Dynamic Reconfigures
|
||||
#include <dynamic_reconfigure/Reconfigure.h>
|
||||
#include <dynamic_reconfigure/Config.h>
|
||||
|
||||
using namespace dynamic_reconfigure;
|
||||
|
||||
int g_interval = 10000; // 10 sec send interval initially, currently not used
|
||||
static size_t g_message_count_send_confirmations = 0;
|
||||
|
||||
|
@ -35,10 +42,7 @@ struct ROS_Azure_IoT_Hub {
|
|||
Parser parser;
|
||||
ros::NodeHandle nh;
|
||||
std::vector<ros::Subscriber> subscribers;
|
||||
std::mutex mtx;
|
||||
std::condition_variable cv;
|
||||
std::vector<std::string> topicsToSubscribe;
|
||||
int signal;
|
||||
};
|
||||
|
||||
static IOTHUBMESSAGE_DISPOSITION_RESULT receive_msg_callback(IOTHUB_MESSAGE_HANDLE message, void* user_context)
|
||||
|
@ -46,7 +50,6 @@ static IOTHUBMESSAGE_DISPOSITION_RESULT receive_msg_callback(IOTHUB_MESSAGE_HAND
|
|||
(void)user_context;
|
||||
const char* messageId;
|
||||
const char* correlationId;
|
||||
|
||||
// Message properties
|
||||
if ((messageId = IoTHubMessage_GetMessageId(message)) == NULL)
|
||||
{
|
||||
|
@ -66,11 +69,11 @@ static IOTHUBMESSAGE_DISPOSITION_RESULT receive_msg_callback(IOTHUB_MESSAGE_HAND
|
|||
|
||||
if (IoTHubMessage_GetByteArray(message, &buff_msg, &buff_len) != IOTHUB_MESSAGE_OK)
|
||||
{
|
||||
(void)printf("Failure retrieving byte array message\r\n");
|
||||
ROS_ERROR("Failure retrieving byte array message");
|
||||
}
|
||||
else
|
||||
{
|
||||
(void)printf("Received Binary message\r\nMessage ID: %s\r\n Correlation ID: %s\r\n Data: <<<%.*s>>> & Size=%d\r\n", messageId, correlationId, (int)buff_len, buff_msg, (int)buff_len);
|
||||
ROS_INFO("Received Binary message\r\n Message ID: %s\r\n Correlation ID: %s\r\n Data: <<<%.*s>>> & Size=%d", messageId, correlationId, (int)buff_len, buff_msg, (int)buff_len);
|
||||
}
|
||||
}
|
||||
else
|
||||
|
@ -78,11 +81,11 @@ static IOTHUBMESSAGE_DISPOSITION_RESULT receive_msg_callback(IOTHUB_MESSAGE_HAND
|
|||
const char* string_msg = IoTHubMessage_GetString(message);
|
||||
if (string_msg == NULL)
|
||||
{
|
||||
(void)printf("Failure retrieving byte array message\r\n");
|
||||
ROS_ERROR("Failure retrieving byte array message");
|
||||
}
|
||||
else
|
||||
{
|
||||
(void)printf("Received String Message\r\nMessage ID: %s\r\n Correlation ID: %s\r\n Data: <<<%s>>>\r\n", messageId, correlationId, string_msg);
|
||||
ROS_INFO("Received String Message\r\n Message ID: %s\r\n Correlation ID: %s\r\n Data: <<<%s>>>", messageId, correlationId, string_msg);
|
||||
}
|
||||
}
|
||||
return IOTHUBMESSAGE_ACCEPTED;
|
||||
|
@ -98,9 +101,9 @@ static int device_method_callback(const char* method_name, const unsigned char*
|
|||
int status = 501;
|
||||
const char* RESPONSE_STRING = "{ \"Response\": \"Unknown method requested.\" }";
|
||||
|
||||
(void)printf("\r\nDevice Method called for device %s\r\n", device_id);
|
||||
(void)printf("Device Method name: %s\r\n", method_name);
|
||||
(void)printf("Device Method payload: %.*s\r\n", (int)size, (const char*)payload);
|
||||
ROS_INFO("Device Method called for device %s", device_id);
|
||||
ROS_INFO("Device Method name: %s", method_name);
|
||||
ROS_INFO("Device Method payload: %.*s", (int)size, (const char*)payload);
|
||||
|
||||
if (strcmp(method_name, SetTelemetryIntervalMethod) == 0)
|
||||
{
|
||||
|
@ -111,7 +114,7 @@ static int device_method_callback(const char* method_name, const unsigned char*
|
|||
// Interval must be greater than zero.
|
||||
if (newInterval > 0)
|
||||
{
|
||||
// expect sec and covert to ms
|
||||
// Expect sec and covert to ms
|
||||
g_interval = 1000 * (int)strtol((char*)payload, &end, 10);
|
||||
status = 200;
|
||||
RESPONSE_STRING = "{ \"Response\": \"Telemetry reporting interval updated.\" }";
|
||||
|
@ -124,8 +127,8 @@ static int device_method_callback(const char* method_name, const unsigned char*
|
|||
}
|
||||
}
|
||||
|
||||
(void)printf("\r\nResponse status: %d\r\n", status);
|
||||
(void)printf("Response payload: %s\r\n\r\n", RESPONSE_STRING);
|
||||
ROS_INFO("Response status: %d", status);
|
||||
ROS_INFO("Response payload: %s", RESPONSE_STRING);
|
||||
|
||||
*resp_size = strlen(RESPONSE_STRING);
|
||||
*response = reinterpret_cast<unsigned char*>(malloc(*resp_size));
|
||||
|
@ -148,11 +151,11 @@ static void connection_status_callback(IOTHUB_CLIENT_CONNECTION_STATUS result, I
|
|||
// This sample DOES NOT take into consideration network outages.
|
||||
if (result == IOTHUB_CLIENT_CONNECTION_AUTHENTICATED)
|
||||
{
|
||||
(void)printf("The device client is connected to iothub\r\n");
|
||||
ROS_INFO("The device client is connected to iothub");
|
||||
}
|
||||
else
|
||||
{
|
||||
(void)printf("The device client has been disconnected\r\n");
|
||||
ROS_INFO("The device client has been disconnected");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -161,13 +164,15 @@ static void send_confirm_callback(IOTHUB_CLIENT_CONFIRMATION_RESULT result, void
|
|||
(void)userContextCallback;
|
||||
// When a message is sent this callback will get envoked
|
||||
g_message_count_send_confirmations++;
|
||||
(void)printf("Confirmation callback received for message %lu with result %s\r\n", (unsigned long)g_message_count_send_confirmations, ENUM_TO_STRING(IOTHUB_CLIENT_CONFIRMATION_RESULT, result));
|
||||
#ifdef _WIN32
|
||||
ROS_INFO("Confirmation callback received for message %lu with result %s", (unsigned long)g_message_count_send_confirmations, ENUM_TO_STRING(IOTHUB_CLIENT_CONFIRMATION_RESULT, result));
|
||||
#else
|
||||
ROS_INFO("Confirmation callback received for message %lu with result %s", (unsigned long)g_message_count_send_confirmations, MU_ENUM_TO_STRING(IOTHUB_CLIENT_CONFIRMATION_RESULT, result));
|
||||
#endif
|
||||
}
|
||||
|
||||
static bool IsTopicAvailableForSubscribe(const char* topicName)
|
||||
{
|
||||
printf("Trying to subscribe: %s\n", topicName);
|
||||
|
||||
std::string topic_name = topicName;
|
||||
|
||||
ros::master::V_TopicInfo advertized_topics;
|
||||
|
@ -184,7 +189,7 @@ static bool IsTopicAvailableForSubscribe(const char* topicName)
|
|||
}
|
||||
if (!found )
|
||||
{
|
||||
printf("This topic has not been published yet: %s\n", topic_name.c_str() );
|
||||
ROS_WARN("This topic has not been published yet: %s", topic_name.c_str());
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -204,9 +209,7 @@ void sendMsgToAzureIoTHub(const char* msg, IOTHUB_DEVICE_CLIENT_HANDLE deviceHan
|
|||
(void)IoTHubMessage_SetContentTypeSystemProperty(message_handle, "application%2fjson");
|
||||
(void)IoTHubMessage_SetContentEncodingSystemProperty(message_handle, "utf-8");
|
||||
|
||||
// Add custom properties to message
|
||||
(void)IoTHubMessage_SetProperty(message_handle, "property_key", "property_value");
|
||||
printf("\r\nSending message %d to IoTHub\r\nMessage: %s\r\n", (int)(messagecount + 1), msg);
|
||||
ROS_INFO("Sending message %d to IoTHub\r\nMessage: %s", (int)(messagecount + 1), msg);
|
||||
IoTHubDeviceClient_SendEventAsync(deviceHandle, message_handle, send_confirm_callback, NULL);
|
||||
|
||||
// The message is copied to the sdk so the we can destroy it
|
||||
|
@ -233,24 +236,24 @@ void topicCallback(const topic_tools::ShapeShifter::ConstPtr& msg,
|
|||
FlatMessage& flat_container = flat_containers[topic_name];
|
||||
RenamedValues& renamed_values = renamed_vectors[topic_name];
|
||||
|
||||
// copy raw memory into the buffer
|
||||
// Copy raw memory into the buffer
|
||||
buffer.resize( msg->size() );
|
||||
ros::serialization::OStream stream(buffer.data(), buffer.size());
|
||||
msg->write(stream);
|
||||
|
||||
// deserialize and rename the vectors
|
||||
// Deserialize and rename the vectors
|
||||
parser.deserializeIntoFlatContainer( topic_name, absl::Span<uint8_t>(buffer), &flat_container, 100);
|
||||
parser.applyNameTransform( topic_name, flat_container, &renamed_values );
|
||||
|
||||
printf("--------- %s ----------\n", topic_name.c_str() );
|
||||
ROS_INFO("--------- %s ----------", topic_name.c_str() );
|
||||
sendMsgToAzureIoTHub(topic_name.c_str(), deviceHandle);
|
||||
for (auto it: renamed_values)
|
||||
{
|
||||
const std::string& key = it.first;
|
||||
const Variant& value = it.second;
|
||||
char buffer [256] = {0};
|
||||
snprintf(buffer, sizeof(buffer), " %s = %f\n", key.c_str(), value.convert<double>());
|
||||
printf("%s",buffer);
|
||||
snprintf(buffer, sizeof(buffer), " %s = %f", key.c_str(), value.convert<double>());
|
||||
ROS_INFO("%s",buffer);
|
||||
sendMsgToAzureIoTHub(buffer, deviceHandle);
|
||||
}
|
||||
for (auto it: flat_container.name)
|
||||
|
@ -258,8 +261,8 @@ void topicCallback(const topic_tools::ShapeShifter::ConstPtr& msg,
|
|||
const std::string& key = it.first.toStdString();
|
||||
const std::string& value = it.second;
|
||||
char buffer [256] = {0};
|
||||
snprintf(buffer, sizeof(buffer), " %s = %s\n", key.c_str(), value.c_str());
|
||||
printf("%s",buffer);
|
||||
snprintf(buffer, sizeof(buffer), " %s = %s", key.c_str(), value.c_str());
|
||||
ROS_INFO("%s",buffer);
|
||||
sendMsgToAzureIoTHub(buffer, deviceHandle);
|
||||
}
|
||||
}
|
||||
|
@ -274,55 +277,156 @@ static void subscribeTopic(const char* topicName, ROS_Azure_IoT_Hub* iotHub)
|
|||
iotHub->subscribers.push_back( iotHub->nh.subscribe(topicName, 10, callback) );
|
||||
}
|
||||
|
||||
//Current code does not keep track of topics already subscribed
|
||||
// Current code does not keep track of topics already subscribed
|
||||
static void deviceTwinCallback(DEVICE_TWIN_UPDATE_STATE update_state, const unsigned char* payLoad, size_t size, void* userContextCallback)
|
||||
{
|
||||
(void)update_state;
|
||||
(void)size;
|
||||
|
||||
|
||||
ROS_Azure_IoT_Hub* iotHub = (ROS_Azure_IoT_Hub*)userContextCallback;
|
||||
|
||||
JSON_Value* root_value = json_parse_string((const char*)payLoad);
|
||||
JSON_Object* root_object = json_value_get_object(root_value);
|
||||
JSON_Object* arrayObject = json_object_dotget_object (root_object, "desired.ros_relays");
|
||||
JSON_Object* desired_object = json_object_dotget_object(root_object, "desired");
|
||||
JSON_Object* ros_object = (desired_object != NULL) ? desired_object : root_object;
|
||||
|
||||
// Get topics for subscription
|
||||
JSON_Object* arrayObject = json_object_dotget_object(ros_object, "ros_relays");
|
||||
size_t objectCount = json_object_get_count(arrayObject);
|
||||
|
||||
for (size_t i = 0; i < objectCount; i++)
|
||||
{
|
||||
printf(" %s \n", json_object_get_name(arrayObject, i));
|
||||
ROS_INFO(" %s", json_object_get_name(arrayObject, i));
|
||||
JSON_Value* value = json_object_get_value_at(arrayObject, i);
|
||||
const char* topicToSubscribe = json_value_get_string(value);
|
||||
printf(" %s \n", json_value_get_string(value));
|
||||
ROS_INFO(" %s", json_value_get_string(value));
|
||||
|
||||
if (IsTopicAvailableForSubscribe(topicToSubscribe))
|
||||
// Only subscribe the topic that is avaiable but not subscribed before
|
||||
if (topicToSubscribe != NULL && IsTopicAvailableForSubscribe(topicToSubscribe) && std::find(iotHub->topicsToSubscribe.begin(), iotHub->topicsToSubscribe.end(), topicToSubscribe) == iotHub->topicsToSubscribe.end())
|
||||
{
|
||||
ROS_INFO("Subscribe topic: %s", topicToSubscribe);
|
||||
iotHub->topicsToSubscribe.push_back(topicToSubscribe);
|
||||
subscribeTopic(topicToSubscribe, iotHub);
|
||||
}
|
||||
}
|
||||
|
||||
std::unique_lock<std::mutex> lck(iotHub->mtx);
|
||||
iotHub->signal = 1;
|
||||
iotHub->cv.notify_all();
|
||||
// Get dynamic reconfiguration settings
|
||||
arrayObject = json_object_dotget_object(ros_object, "ros_dynamic_configurations");
|
||||
objectCount = json_object_get_count(arrayObject);
|
||||
|
||||
for (size_t i = 0; i < objectCount; i++)
|
||||
{
|
||||
JSON_Value* congifure_value = json_object_get_value_at(arrayObject, i);
|
||||
JSON_Object* congifure_object = json_value_get_object(congifure_value);
|
||||
|
||||
const char *node = NULL, *param = NULL, *type = NULL, *value = NULL;
|
||||
JSON_Value* node_value = json_object_get_value(congifure_object, "node");
|
||||
if (node_value != NULL)
|
||||
{
|
||||
node = json_value_get_string(node_value);
|
||||
}
|
||||
|
||||
JSON_Value* param_value = json_object_get_value(congifure_object, "param");
|
||||
if (param_value != NULL)
|
||||
{
|
||||
param = json_value_get_string(param_value);
|
||||
}
|
||||
|
||||
JSON_Value* type_value = json_object_get_value(congifure_object, "type");
|
||||
if (type_value != NULL)
|
||||
{
|
||||
type = json_value_get_string(type_value);
|
||||
}
|
||||
|
||||
JSON_Value* val_value = json_object_get_value(congifure_object, "value");
|
||||
if (val_value != NULL)
|
||||
{
|
||||
value = json_value_get_string(val_value);
|
||||
}
|
||||
|
||||
if (node != NULL && param != NULL && type != NULL && value != NULL)
|
||||
{
|
||||
ROS_INFO("Trying to send dynamic configuration command - node:%s, parameter:%s, data type:%s, value:%s", node, param, type, value);
|
||||
|
||||
ReconfigureRequest srv_req;
|
||||
ReconfigureResponse srv_resp;
|
||||
Config conf;
|
||||
|
||||
if (strcmp(type, "string") == 0)
|
||||
{
|
||||
StrParameter string_param;
|
||||
string_param.name = param;
|
||||
string_param.value = value;
|
||||
conf.strs.push_back(string_param);
|
||||
}
|
||||
else if (strcmp(type, "int") == 0)
|
||||
{
|
||||
char* end = NULL;
|
||||
IntParameter int_param;
|
||||
int_param.name = param;
|
||||
int_param.value = (int)strtol(value, &end, 10);
|
||||
conf.ints.push_back(int_param);
|
||||
}
|
||||
else if (strcmp(type, "double") == 0)
|
||||
{
|
||||
char* end = NULL;
|
||||
DoubleParameter double_param;
|
||||
double_param.name = param;
|
||||
double_param.value = (double)strtod(value, &end);
|
||||
conf.doubles.push_back(double_param);
|
||||
}
|
||||
else if (strcmp(type, "bool") == 0)
|
||||
{
|
||||
try
|
||||
{
|
||||
BoolParameter bool_param;
|
||||
bool_param.name = param;
|
||||
bool_param.value = boost::lexical_cast<bool>(value);
|
||||
conf.bools.push_back(bool_param);
|
||||
}
|
||||
catch (const boost::bad_lexical_cast &e)
|
||||
{
|
||||
(void)e;
|
||||
ROS_ERROR("Failure converting %s to bool type", value);
|
||||
}
|
||||
}
|
||||
|
||||
srv_req.config = conf;
|
||||
char node_set_param[256] = {0};
|
||||
snprintf(node_set_param, sizeof(node_set_param), "%s/set_parameters", node);
|
||||
if (ros::service::call(node_set_param, srv_req, srv_resp))
|
||||
{
|
||||
ROS_INFO("Succeed.");
|
||||
}
|
||||
else
|
||||
{
|
||||
ROS_ERROR("Failure executing the dynamic configuration command.");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Free resources
|
||||
json_value_free(root_value);
|
||||
}
|
||||
|
||||
static int InitializeAzureIoTHub(ROS_Azure_IoT_Hub* iotHub)
|
||||
static bool InitializeAzureIoTHub(ROS_Azure_IoT_Hub* iotHub)
|
||||
{
|
||||
IOTHUB_CLIENT_TRANSPORT_PROVIDER protocol = MQTT_Protocol;
|
||||
|
||||
(void)IoTHub_Init();
|
||||
(void)printf("Creating IoTHub Device handle\r\n");
|
||||
ROS_INFO("Creating IoTHub Device handle");
|
||||
|
||||
ros::NodeHandle nh("~");
|
||||
std::string connectionString;
|
||||
nh.getParam("connection_string", connectionString);
|
||||
(void)printf("connection_string: %s\r\n", connectionString.c_str());
|
||||
ROS_INFO("connection_string: %s", connectionString.c_str());
|
||||
|
||||
// Create the iothub handle here
|
||||
iotHub->deviceHandle = IoTHubDeviceClient_CreateFromConnectionString(connectionString.c_str(), protocol);
|
||||
if (iotHub->deviceHandle == NULL)
|
||||
{
|
||||
(void)printf("Failure createing Iothub device. Hint: Check you connection string.\r\n");
|
||||
return -1;
|
||||
ROS_ERROR("Failure createing Iothub device. Hint: Check you connection string.");
|
||||
return false;
|
||||
}
|
||||
// Setting message callback to get C2D messages
|
||||
(void)IoTHubDeviceClient_SetMessageCallback(iotHub->deviceHandle, receive_msg_callback, NULL);
|
||||
|
@ -333,38 +437,28 @@ static int InitializeAzureIoTHub(ROS_Azure_IoT_Hub* iotHub)
|
|||
(void)IoTHubDeviceClient_SetConnectionStatusCallback(iotHub->deviceHandle, connection_status_callback, NULL);
|
||||
(void)IoTHubDeviceClient_SetDeviceTwinCallback(iotHub->deviceHandle, deviceTwinCallback, iotHub); //Device Twin callback requires context to send message and device Handle
|
||||
|
||||
return 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
static void DeinitializeAzureIoTHub(ROS_Azure_IoT_Hub* iotHub)
|
||||
{
|
||||
ROS_INFO("Deinitializing IoTHub Device client");
|
||||
IoTHubDeviceClient_Destroy(iotHub->deviceHandle);
|
||||
IoTHub_Deinit();
|
||||
}
|
||||
|
||||
int main(int argc, char** argv)
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "ros_azure_iothub");
|
||||
|
||||
ROS_Azure_IoT_Hub iotHub;
|
||||
iotHub.signal = 0;
|
||||
|
||||
if (InitializeAzureIoTHub(&iotHub))
|
||||
if (!InitializeAzureIoTHub(&iotHub))
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
//Wait for the first device twins callback and subscribe to the topics from this callback
|
||||
{
|
||||
std::unique_lock<std::mutex> lck(iotHub.mtx);
|
||||
iotHub.cv.wait(lck, [&iotHub]{return iotHub.signal != 0;});
|
||||
}
|
||||
|
||||
for (auto& it: iotHub.topicsToSubscribe)
|
||||
{
|
||||
(void)printf("%s\r\n", it.c_str());
|
||||
subscribeTopic(it.c_str(), &iotHub);
|
||||
}
|
||||
|
||||
ros::spin();
|
||||
|
||||
IoTHubDeviceClient_Destroy(iotHub.deviceHandle);
|
||||
IoTHub_Deinit();
|
||||
|
||||
DeinitializeAzureIoTHub(&iotHub);
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -0,0 +1,92 @@
|
|||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <azure_c_shared_utility/platform.h>
|
||||
#include <iothub_service_client_auth.h>
|
||||
#include <iothub_devicetwin.h>
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
#include <ros/ros.h>
|
||||
#include <std_msgs/String.h>
|
||||
|
||||
using namespace std;
|
||||
static string connectionString, deviceId;
|
||||
|
||||
// Update device twin desired properties by invoking the Azure IOT Hub Service SDK
|
||||
bool SetDeviceTwin(const char *update_device_twin_json)
|
||||
{
|
||||
bool result = false;
|
||||
|
||||
(void)platform_init();
|
||||
|
||||
IOTHUB_SERVICE_CLIENT_AUTH_HANDLE iotHubServiceClientHandle = IoTHubServiceClientAuth_CreateFromConnectionString(connectionString.c_str());
|
||||
if (iotHubServiceClientHandle != NULL)
|
||||
{
|
||||
IOTHUB_SERVICE_CLIENT_DEVICE_TWIN_HANDLE serviceClientDeviceTwinHandle = IoTHubDeviceTwin_Create(iotHubServiceClientHandle);
|
||||
if (serviceClientDeviceTwinHandle != NULL)
|
||||
{
|
||||
char* deviceTwinJson = NULL;
|
||||
if ((deviceTwinJson = IoTHubDeviceTwin_GetTwin(serviceClientDeviceTwinHandle, deviceId.c_str())) != NULL)
|
||||
{
|
||||
char* updatedDeviceTwinJson = NULL;
|
||||
|
||||
if ((updatedDeviceTwinJson = IoTHubDeviceTwin_UpdateTwin(serviceClientDeviceTwinHandle, deviceId.c_str(), update_device_twin_json)) != NULL)
|
||||
{
|
||||
free(updatedDeviceTwinJson);
|
||||
result = true;
|
||||
}
|
||||
free(deviceTwinJson);
|
||||
}
|
||||
IoTHubDeviceTwin_Destroy(serviceClientDeviceTwinHandle);
|
||||
}
|
||||
IoTHubServiceClientAuth_Destroy(iotHubServiceClientHandle);
|
||||
}
|
||||
|
||||
platform_deinit();
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
TEST(IOTHubTester, ReconfigurationTest)
|
||||
{
|
||||
// Update device twin with the new value for str_param
|
||||
string expectedStr = "ROS_AZURE_IOT_HUB_RECONFIGURATION_TEST_" + std::to_string(ros::Time::now().toSec());
|
||||
string updateJson = "{\"properties\":{\"desired\":{\"ros_dynamic_configurations\":{\"0\":{ \"node\":\"/dynamic_tutorials_node\",\"param\": \"str_param\",\"value\":\"" + expectedStr + "\",\"type\":\"string\"}}}}}";
|
||||
EXPECT_TRUE(SetDeviceTwin(updateJson.c_str()));
|
||||
|
||||
ros::NodeHandle nh;
|
||||
string actualStr;
|
||||
int count = 0;
|
||||
ros::Rate r(1);
|
||||
while (ros::ok() && count < 10)
|
||||
{
|
||||
// Get the dynamic configuration parameter value
|
||||
if (nh.getParam("/dynamic_tutorials_node/str_param", actualStr))
|
||||
{
|
||||
if (expectedStr == actualStr)
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
count++;
|
||||
ros::spinOnce();
|
||||
r.sleep();
|
||||
}
|
||||
|
||||
EXPECT_EQ(expectedStr, actualStr);
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
testing::InitGoogleTest(&argc, argv);
|
||||
ros::init(argc, argv, "azure_iot_hub_test");
|
||||
|
||||
ros::NodeHandle nh("~");
|
||||
nh.getParam("iot_hub_connection_string", connectionString);
|
||||
nh.getParam("device_name", deviceId);
|
||||
|
||||
// Wait 5 seconds to make sure roscpp_azure_iothub_node initialization completes.
|
||||
ros::Duration(5).sleep();
|
||||
return RUN_ALL_TESTS();
|
||||
}
|
|
@ -0,0 +1,22 @@
|
|||
<launch>
|
||||
|
||||
<!-- Parameters for IOT hub connection -->
|
||||
<arg name="device_connection_string" default="HostName=sample.azure-devices.net;DeviceId=rosbot;SharedAccessKey=sampleKey" />
|
||||
<arg name="iot_hub_connection_string" default="HostName=sample.azure-devices.net;SharedAccessKeyName=iothubowner;SharedAccessKey=sampleKey" />
|
||||
<arg name="device_name" default="rosbot" />
|
||||
|
||||
<!-- Launch Azure IOT hub connector -->
|
||||
<node pkg="roscpp_azure_iothub" type="roscpp_azure_iothub_node" name="roscpp_azure_iothub_node" output="screen">
|
||||
<param name="connection_string" value="$(arg device_connection_string)" />
|
||||
</node>
|
||||
|
||||
<!-- Launch dynamic_tutorials test sample -->
|
||||
<node pkg="dynamic_tutorials" type="dynamic_tutorials_node" name="dynamic_tutorials_node" output="screen"/>
|
||||
|
||||
<!-- Run test cases -->
|
||||
<test test-name="roscpp_azure_iothub_testnode" pkg="roscpp_azure_iothub" type="roscpp_azure_iothub_testnode" name="roscpp_azure_iothub_testnode">
|
||||
<param name="iot_hub_connection_string" value="$(arg iot_hub_connection_string)" />
|
||||
<param name="device_name" value="$(arg device_name)" />
|
||||
</test>
|
||||
|
||||
</launch>
|
Загрузка…
Ссылка в новой задаче