in roscpp_azure_iothub/src/ros_azure_iothub_cpp_node.cpp [373:522]
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* 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);
std::string reportedProp = "reported";
for (size_t i = 0; i < objectCount; i++)
{
ROS_INFO(" %s", json_object_get_name(arrayObject, i));
JSON_Value* configure_value = json_object_get_value_at(arrayObject, i);
JSON_Object* configure_object = json_value_get_object(configure_value);
// Get relay method for topic
const char* relay_method = NULL;
JSON_Value* relay_method_value = json_object_get_value(configure_object, "relay_method");
if (relay_method_value != NULL)
{
relay_method = json_value_get_string(relay_method_value);
}
// Get topic name
JSON_Value* topic_value = json_object_get_value(configure_object, "topic");
const char* topicToSubscribe = json_value_get_string(topic_value);
ROS_INFO(" %s", json_value_get_string(topic_value));
// 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);
// Differentiate between topics with different desired relay methods
if (reportedProp.compare(relay_method) == 0)
{
iotHub->topicsToReport.push_back(topicToSubscribe);
}
subscribeTopic(topicToSubscribe, iotHub);
}
}
// 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* configure_value = json_object_get_value_at(arrayObject, i);
JSON_Object* configure_object = json_value_get_object(configure_value);
const char *node = NULL, *param = NULL, *type = NULL, *value = NULL;
JSON_Value* node_value = json_object_get_value(configure_object, "node");
if (node_value != NULL)
{
node = json_value_get_string(node_value);
}
JSON_Value* param_value = json_object_get_value(configure_object, "param");
if (param_value != NULL)
{
param = json_value_get_string(param_value);
}
JSON_Value* type_value = json_object_get_value(configure_object, "type");
if (type_value != NULL)
{
type = json_value_get_string(type_value);
}
JSON_Value* val_value = json_object_get_value(configure_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);
}