Merge pull request #112 from ros2/fix-crash-windows
Remove references to shared pointers
This commit is contained in:
commit
5f573661b3
2 changed files with 16 additions and 16 deletions
|
@ -47,7 +47,7 @@ public:
|
|||
: node_(node)
|
||||
{
|
||||
get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(
|
||||
node_->get_name() + "__get_parameters", [&node](
|
||||
node_->get_name() + "__get_parameters", [node](
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
|
||||
std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> response)
|
||||
|
@ -60,7 +60,7 @@ public:
|
|||
);
|
||||
|
||||
get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
|
||||
node_->get_name() + "__get_parameter_types", [&node](
|
||||
node_->get_name() + "__get_parameter_types", [node](
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
|
||||
std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Response> response)
|
||||
|
@ -74,7 +74,7 @@ public:
|
|||
);
|
||||
|
||||
set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
|
||||
node_->get_name() + "__set_parameters", [&node](
|
||||
node_->get_name() + "__set_parameters", [node](
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
|
||||
std::shared_ptr<rcl_interfaces::srv::SetParameters::Response> response)
|
||||
|
@ -90,7 +90,7 @@ public:
|
|||
|
||||
set_parameters_atomically_service_ =
|
||||
node_->create_service<rcl_interfaces::srv::SetParametersAtomically>(
|
||||
node_->get_name() + "__set_parameters_atomically", [&node](
|
||||
node_->get_name() + "__set_parameters_atomically", [node](
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
|
||||
std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
|
||||
|
@ -108,7 +108,7 @@ public:
|
|||
);
|
||||
|
||||
describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
|
||||
node_->get_name() + "__describe_parameters", [&node](
|
||||
node_->get_name() + "__describe_parameters", [node](
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
|
||||
std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Response> response)
|
||||
|
@ -119,7 +119,7 @@ public:
|
|||
);
|
||||
|
||||
list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
|
||||
node_->get_name() + "__list_parameters", [&node](
|
||||
node_->get_name() + "__list_parameters", [node](
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
|
||||
std::shared_ptr<rcl_interfaces::srv::ListParameters::Response> response)
|
||||
|
|
|
@ -78,8 +78,8 @@ public:
|
|||
virtual std::shared_ptr<void> create_request() = 0;
|
||||
virtual std::shared_ptr<void> create_request_header() = 0;
|
||||
virtual void handle_request(
|
||||
std::shared_ptr<void> & request_header,
|
||||
std::shared_ptr<void> & request) = 0;
|
||||
std::shared_ptr<void> request_header,
|
||||
std::shared_ptr<void> request) = 0;
|
||||
|
||||
private:
|
||||
RCLCPP_DISABLE_COPY(ServiceBase);
|
||||
|
@ -97,14 +97,14 @@ class Service : public ServiceBase
|
|||
public:
|
||||
using CallbackType = std::function<
|
||||
void(
|
||||
const std::shared_ptr<typename ServiceT::Request> &,
|
||||
std::shared_ptr<typename ServiceT::Response> &)>;
|
||||
const std::shared_ptr<typename ServiceT::Request>,
|
||||
std::shared_ptr<typename ServiceT::Response>)>;
|
||||
|
||||
using CallbackWithHeaderType = std::function<
|
||||
void(
|
||||
const std::shared_ptr<rmw_request_id_t> &,
|
||||
const std::shared_ptr<typename ServiceT::Request> &,
|
||||
std::shared_ptr<typename ServiceT::Response> &)>;
|
||||
const std::shared_ptr<rmw_request_id_t>,
|
||||
const std::shared_ptr<typename ServiceT::Request>,
|
||||
std::shared_ptr<typename ServiceT::Response>)>;
|
||||
RCLCPP_SMART_PTR_DEFINITIONS(Service);
|
||||
|
||||
Service(
|
||||
|
@ -137,7 +137,7 @@ public:
|
|||
return std::shared_ptr<void>(new rmw_request_id_t);
|
||||
}
|
||||
|
||||
void handle_request(std::shared_ptr<void> & request_header, std::shared_ptr<void> & request)
|
||||
void handle_request(std::shared_ptr<void> request_header, std::shared_ptr<void> request)
|
||||
{
|
||||
auto typed_request = std::static_pointer_cast<typename ServiceT::Request>(request);
|
||||
auto typed_request_header = std::static_pointer_cast<rmw_request_id_t>(request_header);
|
||||
|
@ -151,8 +151,8 @@ public:
|
|||
}
|
||||
|
||||
void send_response(
|
||||
std::shared_ptr<rmw_request_id_t> & req_id,
|
||||
std::shared_ptr<typename ServiceT::Response> & response)
|
||||
std::shared_ptr<rmw_request_id_t> req_id,
|
||||
std::shared_ptr<typename ServiceT::Response> response)
|
||||
{
|
||||
rmw_ret_t status = rmw_send_response(get_service_handle(), req_id.get(), response.get());
|
||||
if (status != RMW_RET_OK) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue