Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update for rclcpp namespace removals > > connects to ros2/rclcpp#416 #52

Merged
merged 5 commits into from
Dec 5, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions tf2_ros/include/tf2_ros/static_transform_broadcaster.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class StaticTransformBroadcaster{
public:

TF2_ROS_PUBLIC
StaticTransformBroadcaster(rclcpp::node::Node::SharedPtr node);
StaticTransformBroadcaster(rclcpp::Node::SharedPtr node);

/** \brief Send a TransformStamped message
* The stamped data structure includes frame_id, and time, and parent_id already. */
Expand All @@ -66,8 +66,8 @@ class StaticTransformBroadcaster{

private:
/// Internal reference to ros::Node
rclcpp::node::Node::SharedPtr node_;
rclcpp::publisher::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
rclcpp::Node::SharedPtr node_;
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
tf2_msgs::msg::TFMessage net_message_;

};
Expand Down
6 changes: 3 additions & 3 deletions tf2_ros/include/tf2_ros/transform_broadcaster.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class TransformBroadcaster{
public:
/** \brief Constructor (needs a ros::Node reference) */
TF2_ROS_PUBLIC
TransformBroadcaster(rclcpp::node::Node::SharedPtr node);
TransformBroadcaster(rclcpp::Node::SharedPtr node);

/** \brief Send a StampedTransform
* The stamped data structure includes frame_id, and time, and parent_id already. */
Expand All @@ -71,8 +71,8 @@ class TransformBroadcaster{

private:
/// Internal reference to ros::Node
rclcpp::node::Node::SharedPtr node_;
rclcpp::publisher::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
rclcpp::Node::SharedPtr node_;
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;

};

Expand Down
8 changes: 4 additions & 4 deletions tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class TransformListener
TransformListener(tf2::BufferCore& buffer, bool spin_thread = true);

TF2_ROS_PUBLIC
TransformListener(tf2::BufferCore& buffer, rclcpp::node::Node::SharedPtr nh, bool spin_thread = true);
TransformListener(tf2::BufferCore& buffer, rclcpp::Node::SharedPtr nh, bool spin_thread = true);

TF2_ROS_PUBLIC
~TransformListener();
Expand All @@ -70,9 +70,9 @@ class TransformListener

// ros::CallbackQueue tf_message_callback_queue_;
std::thread* dedicated_listener_thread_;
rclcpp::node::Node::SharedPtr node_;
rclcpp::subscription::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;
rclcpp::subscription::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_static_;
rclcpp::Node::SharedPtr node_;
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_static_;
tf2::BufferCore& buffer_;
bool using_dedicated_thread_;
tf2::TimePoint last_update_;
Expand Down
2 changes: 1 addition & 1 deletion tf2_ros/src/buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ Buffer::Buffer(tf2::Duration cache_time, bool debug) :
BufferCore(cache_time)
{
// TODO(tfoote) reenable
// if(debug && !ros::service::exists("~tf2_frames", false))
// if(debug && !ros::exists("~tf2_frames", false))
// {
// ros::NodeHandle n("~");
// frames_server_ = n.advertiseService("tf2_frames", &Buffer::getFrames, this);
Expand Down
2 changes: 1 addition & 1 deletion tf2_ros/src/static_transform_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

namespace tf2_ros {

StaticTransformBroadcaster::StaticTransformBroadcaster(rclcpp::node::Node::SharedPtr node):
StaticTransformBroadcaster::StaticTransformBroadcaster(rclcpp::Node::SharedPtr node):
node_(node)
{
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
Expand Down
2 changes: 1 addition & 1 deletion tf2_ros/src/static_transform_broadcaster_program.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ int main(int argc, char ** argv)
rclcpp::init(argc, argv);

// TODO(clalancette): Anonymize the node name like it is in ROS1.
auto node = rclcpp::node::Node::make_shared("static_transform_publisher");
auto node = rclcpp::Node::make_shared("static_transform_publisher");

rclcpp::TimeSource ts(node);
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
Expand Down
4 changes: 2 additions & 2 deletions tf2_ros/src/tf2_echo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ int main(int argc, char ** argv)
//TODO(tfoote) restore anonymous??
// ros::init_options::AnonymousName);

rclcpp::node::Node::SharedPtr nh = rclcpp::node::Node::make_shared("tf2_echo");
rclcpp::Node::SharedPtr nh = rclcpp::Node::make_shared("tf2_echo");

double rate_hz;
if (argc == 4)
Expand All @@ -92,7 +92,7 @@ int main(int argc, char ** argv)
// ros::NodeHandle p_nh("~");
// p_nh.param("rate", rate_hz, 1.0);
}
rclcpp::rate::Rate rate(rate_hz);
rclcpp::Rate rate(rate_hz);

//Instantiate a local listener
echoListener echoListener;
Expand Down
10 changes: 5 additions & 5 deletions tf2_ros/src/tf2_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ class TFMonitor
std::string framea_, frameb_;
bool using_specific_chain_;

rclcpp::node::Node::SharedPtr node_;
rclcpp::subscription::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr subscriber_tf_, subscriber_tf_message_;
rclcpp::Node::SharedPtr node_;
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr subscriber_tf_, subscriber_tf_message_;
std::vector<std::string> chain_;
std::map<std::string, std::string> frame_authority_map;
std::map<std::string, std::vector<double> > delay_map;
Expand Down Expand Up @@ -125,7 +125,7 @@ class TFMonitor
};

TFMonitor(
rclcpp::node::Node::SharedPtr node, bool using_specific_chain,
rclcpp::Node::SharedPtr node, bool using_specific_chain,
std::string framea = "", std::string frameb = "")
: node_(node),
framea_(framea),
Expand Down Expand Up @@ -274,7 +274,7 @@ int main(int argc, char ** argv)
rclcpp::init(argc, argv);

//TODO(tfoote) make anonymous
rclcpp::node::Node::SharedPtr nh = rclcpp::node::Node::make_shared("tf2_monitor_main");
rclcpp::Node::SharedPtr nh = rclcpp::Node::make_shared("tf2_monitor_main");


std::string framea, frameb;
Expand Down Expand Up @@ -307,7 +307,7 @@ int main(int argc, char ** argv)
// rclcpp::spin, since there are more than one versions of it (overloaded).
// see: http://stackoverflow.com/a/27389714/671658
// I (wjwwood) chose to use the lamda rather than the static cast solution.
auto run_func = [](rclcpp::node::Node::SharedPtr node) {
auto run_func = [](rclcpp::Node::SharedPtr node) {
return rclcpp::spin(node);
};
TFMonitor monitor(nh, using_specific_chain, framea, frameb);
Expand Down
2 changes: 1 addition & 1 deletion tf2_ros/src/transform_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

namespace tf2_ros {

TransformBroadcaster::TransformBroadcaster(rclcpp::node::Node::SharedPtr node) :
TransformBroadcaster::TransformBroadcaster(rclcpp::Node::SharedPtr node) :
node_(node)
{
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
Expand Down
6 changes: 3 additions & 3 deletions tf2_ros/src/transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,13 @@ TransformListener::TransformListener(tf2::BufferCore& buffer, bool spin_thread):
dedicated_listener_thread_(NULL), buffer_(buffer), using_dedicated_thread_(false)
{
//TODO(tfoote)make this anonymous
node_ = rclcpp::node::Node::make_shared("transform_listener_impl");
node_ = rclcpp::Node::make_shared("transform_listener_impl");
init();
if (spin_thread)
initThread();
}

TransformListener::TransformListener(tf2::BufferCore& buffer, rclcpp::node::Node::SharedPtr nh, bool spin_thread)
TransformListener::TransformListener(tf2::BufferCore& buffer, rclcpp::Node::SharedPtr nh, bool spin_thread)
: dedicated_listener_thread_(NULL)
, node_(nh)
, buffer_(buffer)
Expand Down Expand Up @@ -93,7 +93,7 @@ void TransformListener::initThread()
// rclcpp::spin, since there are more than one versions of it (overloaded).
// see: http://stackoverflow.com/a/27389714/671658
// I (wjwwood) chose to use the lamda rather than the static cast solution.
auto run_func = [](rclcpp::node::Node::SharedPtr node) {
auto run_func = [](rclcpp::Node::SharedPtr node) {
return rclcpp::spin(node);
};
dedicated_listener_thread_ = new std::thread(run_func, node_);
Expand Down