Skip to content

Commit

Permalink
Fix clang compilation errors (#119)
Browse files Browse the repository at this point in the history
**Public-Facing Changes**
None


**Description**
- Fix clang compilation errors
  - [x] ROS2
  - [x] ROS1

Fixes #118
  • Loading branch information
achim-k committed Dec 19, 2022
1 parent 8fccb98 commit eca7a5c
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,13 @@

namespace foxglove {

inline void to_json(nlohmann::json& j, const ClientAdvertisement& p) {
j = nlohmann::json{{"id", p.channelId},
{"topic", p.topic},
{"encoding", p.encoding},
{"schemaName", p.schemaName}};
}

using TextMessageHandler = std::function<void(const std::string&)>;
using BinaryMessageHandler = std::function<void(const uint8_t*, size_t)>;
using OpCode = websocketpp::frame::opcode::value;
Expand Down Expand Up @@ -197,11 +204,4 @@ class Client : public ClientInterface {
BinaryMessageHandler _binaryMessageHandler;
};

inline void to_json(nlohmann::json& j, const ClientAdvertisement& p) {
j = nlohmann::json{{"id", p.channelId},
{"topic", p.topic},
{"encoding", p.encoding},
{"schemaName", p.schemaName}};
}

} // namespace foxglove
17 changes: 11 additions & 6 deletions foxglove_bridge_base/include/foxglove_bridge/websocket_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ static const websocketpp::log::level RECOVERABLE = websocketpp::log::elevel::rer
constexpr uint32_t Integer(const std::string_view str) {
uint32_t result = 0x811C9DC5; // FNV-1a 32-bit algorithm
for (char c : str) {
result = (c ^ result) * 0x01000193;
result = (static_cast<uint32_t>(c) ^ result) * 0x01000193;
}
return result;
}
Expand Down Expand Up @@ -127,6 +127,7 @@ class ServerInterface {
using ClientMessageHandler = std::function<void(const ClientMessage&, ConnHandle)>;

public:
virtual ~ServerInterface() {}
virtual void start(const std::string& host, uint16_t port) = 0;
virtual void stop() = 0;

Expand Down Expand Up @@ -700,9 +701,9 @@ inline void Server<ServerConfiguration>::handleTextMessage(ConnHandle hdl, const
template <typename ServerConfiguration>
inline void Server<ServerConfiguration>::handleBinaryMessage(ConnHandle hdl, const uint8_t* msg,
size_t length) {
const uint64_t timestamp = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::high_resolution_clock::now().time_since_epoch())
.count();
const auto timestamp = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::high_resolution_clock::now().time_since_epoch())
.count();

if (length < 1) {
sendStatus(hdl, StatusLevel::Error, "Received an empty binary message");
Expand Down Expand Up @@ -737,8 +738,12 @@ inline void Server<ServerConfiguration>::handleBinaryMessage(ConnHandle hdl, con
if (_clientMessageHandler) {
const auto& advertisement = channelIt->second;
const uint32_t sequence = 0;
const ClientMessage clientMessage{timestamp, timestamp, sequence,
advertisement, length, msg};
const ClientMessage clientMessage{static_cast<uint64_t>(timestamp),
static_cast<uint64_t>(timestamp),
sequence,
advertisement,
length,
msg};
_clientMessageHandler(clientMessage, hdl);
}
} break;
Expand Down
2 changes: 1 addition & 1 deletion ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ class FoxgloveBridge : public rclcpp::Node {
this->set_parameter(rclcpp::Parameter{"port", listeningPort});
}

_maxQosDepth = this->get_parameter("max_qos_depth").as_int();
_maxQosDepth = static_cast<size_t>(this->get_parameter("max_qos_depth").as_int());

// Start the thread polling for rosgraph changes
_rosgraphPollThread =
Expand Down
1 change: 0 additions & 1 deletion ros2_foxglove_bridge/src/ros2_foxglove_bridge_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ int main(int argc, char* argv[]) {

rclcpp_components::ComponentManager componentManager(executor, "ComponentManager");
const auto componentResources = componentManager.get_component_resources("foxglove_bridge");
RCLCPP_INFO(componentManager.get_logger(), std::to_string(numThreads).c_str());

if (componentResources.empty()) {
RCLCPP_INFO(componentManager.get_logger(), "No loadable resources found");
Expand Down
2 changes: 1 addition & 1 deletion ros2_foxglove_bridge/tests/smoke_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ TEST(SmokeTest, testPublishing) {
auto msgFuture = msgPromise.get_future();
auto node = rclcpp::Node::make_shared("tester");
auto sub = node->create_subscription<std_msgs::msg::String>(
advertisement.topic, 10, [&msgPromise, &node](const std_msgs::msg::String::SharedPtr msg) {
advertisement.topic, 10, [&msgPromise](const std_msgs::msg::String::SharedPtr msg) {
msgPromise.set_value(msg->data);
});
rclcpp::executors::SingleThreadedExecutor executor;
Expand Down

0 comments on commit eca7a5c

Please sign in to comment.