Skip to content

Commit

Permalink
Merge pull request #78 from lge-ros2/main
Browse files Browse the repository at this point in the history
Merge into jazzy
  • Loading branch information
hyunseok-yang authored Jul 22, 2024
2 parents 099f4fd + 6c2b27e commit 16b6545
Show file tree
Hide file tree
Showing 78 changed files with 682 additions and 490 deletions.
2 changes: 1 addition & 1 deletion cloisim_ros_actor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>cloisim_ros_actor</name>
<version>4.3.0</version>
<version>4.3.1</version>
<description>node for actor plugin</description>
<maintainer email="hyunseok7.yang@lge.com">Hyunseok Yang</maintainer>
<license>MIT</license>
Expand Down
19 changes: 10 additions & 9 deletions cloisim_ros_actor/src/actor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,10 @@

#include "cloisim_ros_actor/actor.hpp"

using namespace std;
using namespace std::placeholders;
using namespace cloisim;
using Param = cloisim::msgs::Param;
using Any = cloisim::msgs::Any;
using string = std::string;

namespace cloisim_ros
{
Expand Down Expand Up @@ -59,9 +60,9 @@ void Actor::Initialize()
}

void Actor::CallMoveActor(
const shared_ptr<rmw_request_id_t> /*request_header*/,
const shared_ptr<cloisim_ros_msgs::srv::MoveActor::Request> request,
const shared_ptr<cloisim_ros_msgs::srv::MoveActor::Response> response)
const std::shared_ptr<rmw_request_id_t> /*request_header*/,
const std::shared_ptr<cloisim_ros_msgs::srv::MoveActor::Request> request,
const std::shared_ptr<cloisim_ros_msgs::srv::MoveActor::Response> response)
{
const auto message = CreateMoveRequest(request->target_name, request->destination);
const auto reply = RequestReplyMessage(control_bridge_ptr, message);
Expand All @@ -71,7 +72,7 @@ void Actor::CallMoveActor(
}
}

bool Actor::GetResultFromResponse(const msgs::Param &response_msg)
bool Actor::GetResultFromResponse(const Param &response_msg)
{
if (!response_msg.IsInitialized() || response_msg.name().compare("result") != 0)
{
Expand All @@ -80,15 +81,15 @@ bool Actor::GetResultFromResponse(const msgs::Param &response_msg)
return response_msg.value().bool_value();
}

msgs::Param Actor::CreateMoveRequest(
Param Actor::CreateMoveRequest(
const string target_name,
const geometry_msgs::msg::Vector3 point)
{
msgs::Param request_msg;
Param request_msg;
request_msg.set_name(target_name);

auto value_ptr = request_msg.mutable_value();
value_ptr->set_type(msgs::Any::VECTOR3D);
value_ptr->set_type(Any::VECTOR3D);

auto vector3d_value_ptr = value_ptr->mutable_vector3d_value();
vector3d_value_ptr->set_x(point.x);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* @file camera_helper.h
* @file camera_helper.hpp
* @date 2021-05-16
* @author Hyunseok Yang
* @brief
Expand All @@ -13,8 +13,8 @@
* SPDX-License-Identifier: MIT
*/

#ifndef CLOISIM_ROS_BASE__CAMERA_HELPER_H_
#define CLOISIM_ROS_BASE__CAMERA_HELPER_H_
#ifndef CLOISIM_ROS_BASE__CAMERA_HELPER_HPP_
#define CLOISIM_ROS_BASE__CAMERA_HELPER_HPP_

#include <cloisim_msgs/camerasensor.pb.h>
#include <cloisim_msgs/param.pb.h>
Expand Down Expand Up @@ -178,4 +178,4 @@ static cloisim::msgs::CameraSensor GetCameraSensorMessage(
return cameraSensorInfo;
}

#endif // CLOISIM_ROS_BASE__CAMERA_HELPER_H_
#endif // CLOISIM_ROS_BASE__CAMERA_HELPER_HPP_
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* @file helper.h
* @file helper.hpp
* @date 2021-01-14
* @author Hyunseok Yang
* @brief
Expand All @@ -13,8 +13,8 @@
* SPDX-License-Identifier: MIT
*/

#ifndef CLOISIM_ROS_BASE__HELPER_H_
#define CLOISIM_ROS_BASE__HELPER_H_
#ifndef CLOISIM_ROS_BASE__HELPER_HPP_
#define CLOISIM_ROS_BASE__HELPER_HPP_

#include <tf2/LinearMath/Quaternion.h>

Expand Down Expand Up @@ -114,4 +114,4 @@ static void ConvertPointToVector3(
dst.z = src.z;
}

#endif // CLOISIM_ROS_BASE__HELPER_H_
#endif // CLOISIM_ROS_BASE__HELPER_HPP_
2 changes: 1 addition & 1 deletion cloisim_ros_base/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>cloisim_ros_base</name>
<version>4.3.0</version>
<version>4.3.1</version>
<description>CLOiSim-ROS base class for other CLOiSim-ROS</description>
<maintainer email="hyunseok7.yang@lge.com">Hyunseok Yang</maintainer>
<license>MIT</license>
Expand Down
62 changes: 34 additions & 28 deletions cloisim_ros_base/src/base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
#include <cloisim_msgs/transform_stamped.pb.h>

#include "cloisim_ros_base/base.hpp"
#include "cloisim_ros_base/helper.h"
#include "cloisim_ros_base/helper.hpp"

using namespace std;
using namespace cloisim;
using namespace std::literals::chrono_literals;
using string = std::string;

namespace cloisim_ros
{
Expand All @@ -45,16 +45,16 @@ Base::Base(const string node_name, const string namespace_, const rclcpp::NodeOp
rclcpp::NodeOptions(options)
.automatically_declare_parameters_from_overrides(true)
.append_parameter_override("use_sim_time", true)
.arguments(vector<string>{"--ros-args",
"--remap", "/tf:=tf",
"--remap", "/tf_static:=tf_static"}))
.arguments(std::vector<string>{"--ros-args",
"--remap", "/tf:=tf",
"--remap", "/tf_static:=tf_static"}))
, m_bRunThread(false)
, m_node_handle(shared_ptr<rclcpp::Node>(this, [](auto) {}))
, m_node_handle(std::shared_ptr<rclcpp::Node>(this, [](auto) {}))
, m_static_tf_broadcaster(nullptr)
, m_tf_broadcaster(nullptr)
, enable_tf_publish_(true)
{
get_parameter_or("enable_tf", enable_tf_publish_, bool(true));
get_parameter_or("enable_tf", enable_tf_publish_, true);
}

Base::~Base()
Expand Down Expand Up @@ -117,7 +117,9 @@ void Base::GenerateTF(const string& buffer)
newTf.header.stamp = Convert(pb_transform_stamped.header().stamp());
newTf.header.frame_id = pb_transform_stamped.header().str_id();
newTf.child_frame_id = pb_transform_stamped.transform().name();
// DBG_SIM_INFO("%ld %ld %s %s", newTf.header.stamp.sec, newTf.header.stamp.nanosec, newTf.header.frame_id.c_str(), newTf.child_frame_id.c_str());
// DBG_SIM_INFO("%ld %ld %s %s",
// newTf.header.stamp.sec, newTf.header.stamp.nanosec,
// newTf.header.frame_id.c_str(), newTf.child_frame_id.c_str());
SetTf2(newTf,
pb_transform_stamped.transform(),
pb_transform_stamped.transform().name(),
Expand Down Expand Up @@ -161,7 +163,7 @@ void Base::CloseBridges()

void Base::AddPublisherThread(
zmq::Bridge* const bridge_ptr,
function<void(const string&)> thread_func)
std::function<void(const string&)> thread_func)
{
m_threads.emplace_back(
[this, bridge_ptr, thread_func]()
Expand All @@ -173,7 +175,8 @@ void Base::AddPublisherThread(
const bool succeeded = GetBufferFromSimulator(bridge_ptr, &buffer_ptr, bufferLength);
if (!succeeded || bufferLength < 0)
{
DBG_ERR("[%s] Failed to get buffer(%d) <= Sim, %s", get_name(), bufferLength, zmq_strerror(zmq_errno()));
DBG_ERR("[%s] Failed to get buffer(%d) <= Sim, %s",
get_name(), bufferLength, zmq_strerror(zmq_errno()));
continue;
}

Expand Down Expand Up @@ -221,7 +224,7 @@ void Base::GetStaticTransforms(zmq::Bridge* const bridge_ptr)
{
if (link.IsInitialized() && link.has_name() && link.has_value())
{
const auto parent_frame_id = (link.value().type() == msgs::Any_ValueType_STRING &&
const auto parent_frame_id = (link.value().type() == cloisim::msgs::Any_ValueType_STRING &&
link.name().compare("parent_frame_id") == 0)
? link.value().string_value()
: "base_link";
Expand All @@ -233,7 +236,7 @@ void Base::GetStaticTransforms(zmq::Bridge* const bridge_ptr)
if (child.has_name() && child.has_value())
{
if ((child.name().compare("pose") == 0) &&
child.value().type() == msgs::Any_ValueType_POSE3D)
child.value().type() == cloisim::msgs::Any_ValueType_POSE3D)
{
pose = child.value().pose3d_value();
}
Expand All @@ -247,12 +250,12 @@ void Base::GetStaticTransforms(zmq::Bridge* const bridge_ptr)
}
}

msgs::Pose Base::GetObjectTransform(
cloisim::msgs::Pose Base::GetObjectTransform(
zmq::Bridge* const bridge_ptr,
const string target_name,
string& parent_frame_id)
{
msgs::Pose transform;
cloisim::msgs::Pose transform;
transform.Clear();

if (bridge_ptr == nullptr)
Expand All @@ -272,7 +275,7 @@ msgs::Pose Base::GetObjectTransform(
{
const auto child_param = reply.children(0);
if (child_param.name() == "parent_frame_id" && child_param.has_value() &&
child_param.value().type() == msgs::Any_ValueType_STRING &&
child_param.value().type() == cloisim::msgs::Any_ValueType_STRING &&
!child_param.value().string_value().empty())
{
// set parent_frame_id into name if exists.
Expand Down Expand Up @@ -303,7 +306,7 @@ void Base::GetRos2Parameter(zmq::Bridge* const bridge_ptr)
{
const auto param = reply.children(i);
const auto paramValue = (param.has_value() &&
param.value().type() == msgs::Any_ValueType_STRING)
param.value().type() == cloisim::msgs::Any_ValueType_STRING)
? param.value().string_value()
: "";

Expand Down Expand Up @@ -347,7 +350,7 @@ bool Base::GetBufferFromSimulator(

void Base::SetTf2(
geometry_msgs::msg::TransformStamped& target_msg,
const msgs::Pose transform,
const cloisim::msgs::Pose transform,
const string child_frame_id,
const string header_frame_id)
{
Expand All @@ -358,7 +361,7 @@ void Base::SetTf2(
}

void Base::SetStaticTf2(
const msgs::Pose transform,
const cloisim::msgs::Pose transform,
const string parent_header_frame_id)
{
geometry_msgs::msg::TransformStamped static_tf;
Expand All @@ -370,12 +373,12 @@ void Base::SetStaticTf2(
AddStaticTf2(static_tf);
}

msgs::Param Base::RequestReplyMessage(
cloisim::msgs::Param Base::RequestReplyMessage(
zmq::Bridge* const bridge_ptr,
const string request_message,
const string request_value)
{
msgs::Param reply;
cloisim::msgs::Param reply;

if (bridge_ptr == nullptr)
{
Expand All @@ -384,7 +387,7 @@ msgs::Param Base::RequestReplyMessage(
}

string serialized_request_data;
msgs::Param request;
cloisim::msgs::Param request;
request.set_name(request_message);

if (!request_value.empty())
Expand All @@ -401,19 +404,22 @@ msgs::Param Base::RequestReplyMessage(
if (serialized_reply_data.size() > 0)
{
if (reply.ParseFromString(serialized_reply_data) == false)
DBG_SIM_ERR("Failed to parse serialized buffer, buffer_ptr(%p) length(%ld)", serialized_reply_data.data(), serialized_reply_data.size());
{
DBG_SIM_ERR("Failed to parse serialized buffer, buffer_ptr(%p) length(%ld)",
serialized_reply_data.data(), serialized_reply_data.size());
}
}
else
DBG_SIM_ERR("Failed to get reply data, length(%ld)", serialized_reply_data.size());

return reply;
}

msgs::Param Base::RequestReplyMessage(
cloisim::msgs::Param Base::RequestReplyMessage(
zmq::Bridge* const bridge_ptr,
const msgs::Param request_message)
const cloisim::msgs::Param request_message)
{
msgs::Param response_msg;
cloisim::msgs::Param response_msg;

string serializedBuffer;
request_message.SerializeToString(&serializedBuffer);
Expand All @@ -427,9 +433,9 @@ msgs::Param Base::RequestReplyMessage(
return response_msg;
}

msgs::Pose Base::IdentityPose()
cloisim::msgs::Pose Base::IdentityPose()
{
msgs::Pose identityTransform;
cloisim::msgs::Pose identityTransform;
identityTransform.mutable_position()->set_x(0.0);
identityTransform.mutable_position()->set_y(0.0);
identityTransform.mutable_position()->set_z(0.0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,9 @@
#define CLOISIM_ROS_BRIDGE_ZMQ__BRIDGE_HPP_

#include <zmq.h>

#include "log.h"

#include <string>
#include "cloisim_ros_bridge_zmq/log.h"


namespace cloisim_ros
{
Expand Down Expand Up @@ -85,7 +84,7 @@ class Bridge

private:
bool Setup(const unsigned char mode);
bool SetupCommon(void* const targetSocket);
bool SetupCommon(void* const socket);
bool SetupSubscriber();
bool SetupPublisher();
bool SetupService();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef CLOISIM_ROS_BRIDGE_ZMQ__LOG_H_
#define CLOISIM_ROS_BRIDGE_ZMQ__LOG_H_

#include "term_color.h"
#include "cloisim_ros_bridge_zmq/term_color.h"

#pragma GCC system_header

Expand Down
2 changes: 1 addition & 1 deletion cloisim_ros_bridge_zmq/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>cloisim_ros_bridge_zmq</name>
<version>4.3.0</version>
<version>4.3.1</version>
<description>bridge for cloisim(simulator) connection through ZMQ</description>
<maintainer email="hyunseok7.yang@lge.com">Hyunseok Yang</maintainer>
<license>MIT</license>
Expand Down
Loading

0 comments on commit 16b6545

Please sign in to comment.