void topicCallback()

in roscpp_azure_iothub/src/ros_azure_iothub_cpp_node.cpp [268:359]


void topicCallback(const topic_tools::ShapeShifter::ConstPtr& msg,
                   const std::string &topic_name,
                   RosIntrospection::Parser& parser,
                   IOTHUB_DEVICE_CLIENT_HANDLE deviceHandle, 
                   std::vector<std::string> topicsToReport,
                   char* reportedProperties)
{
    const std::string&  datatype   =  msg->getDataType();
    const std::string&  definition =  msg->getMessageDefinition();

    parser.registerMessageDefinition( topic_name,
                                      RosIntrospection::ROSType(datatype),
                                      definition );

    static std::vector<uint8_t> buffer;
    static std::map<std::string,FlatMessage>   flat_containers;
    static std::map<std::string,RenamedValues> renamed_vectors;

    FlatMessage&   flat_container = flat_containers[topic_name];
    RenamedValues& renamed_values = renamed_vectors[topic_name];

    // Copy raw memory into the buffer
    buffer.resize( msg->size() );
    ros::serialization::OStream stream(buffer.data(), (uint32_t)buffer.size());
    msg->write(stream);

    // Deserialize and rename the vectors
    parser.deserializeIntoFlatContainer( topic_name, Span<uint8_t>(buffer), &flat_container, 100);
    parser.applyNameTransform( topic_name, flat_container, &renamed_values );

    // Send info to IoTHub via reported properties
    // ref: https://docs.microsoft.com/en-us/azure/iot-hub/iot-hub-devguide-device-twins#tags-and-properties-format
    if (!(std::find(topicsToReport.begin(), topicsToReport.end(), topic_name.c_str()) == topicsToReport.end()))
    {
        ROS_DEBUG("Sending message from %s to IoTHub via reported properties ", topic_name.c_str()); 

        std::string topic_msg = "";
      
        for (auto it: renamed_values)
        {
            const std::string& key = it.first;
            const Variant& value   = it.second;
            char char_buffer [256] = {0};
            if (key.find('.')!=std::string::npos)
            {
                ROS_DEBUG_STREAM("Device twin doesn't support key with dots `.`: " << key);
                continue;
            }
            snprintf(char_buffer, sizeof(char_buffer), "\"%s\":\"%f\"", key.c_str(), value.convert<double>());
            buildReportedString(topic_msg, (std::string)char_buffer);
        }
        for (auto it: flat_container.name)
        {
            const std::string& key    = it.first.toStdString();
            const std::string& value  = it.second;
            char char_buffer [256] = {0};
            if (key.find('.')!=std::string::npos)
            {
                ROS_DEBUG_STREAM("Device twin doesn't support key with dots `.`: " << key);
                continue;
            }
            snprintf(char_buffer, sizeof(char_buffer), "\"%s\":\"%s\"", key.c_str(), value.c_str());
            buildReportedString(topic_msg, (std::string)char_buffer);
        }

        reportedProperties = serializeToJson(topic_name, topic_msg);
        (void)IoTHubDeviceClient_SendReportedState(deviceHandle, (const unsigned char*)reportedProperties, strlen(reportedProperties), reportedStateCallback, NULL);
    }
    else // Send info to IoTHub via telemetry 
    {
        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 char_buffer [256] = {0};
            snprintf(char_buffer, sizeof(char_buffer), " %s = %f", key.c_str(), value.convert<double>());
            ROS_INFO("%s",char_buffer);
            sendMsgToAzureIoTHub(char_buffer, deviceHandle);
        }
        for (auto it: flat_container.name)
        {
            const std::string& key    = it.first.toStdString();
            const std::string& value  = it.second;
            char char_buffer [256] = {0};
            snprintf(char_buffer, sizeof(char_buffer), " %s = %s", key.c_str(), value.c_str());
            ROS_INFO("%s",char_buffer);
            sendMsgToAzureIoTHub(char_buffer, deviceHandle);
        }
    }
}