NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
ros_pose_rapid_position.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 
19 #ifndef DDS_ROS_BRIDGE_ROS_POSE_RAPID_POSITION_H_
20 #define DDS_ROS_BRIDGE_ROS_POSE_RAPID_POSITION_H_
21 
22 #include <string>
23 
24 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
26 #include "dds_ros_bridge/util.h"
27 
28 #include "geometry_msgs/PoseStamped.h"
29 
30 #include "knDds/DdsTypedSupplier.h"
31 
32 #include "rapidDds/RapidConstants.h"
33 
34 #include "rapidIo/RapidIoParameters.h"
35 
36 #include "rapidUtil/RapidHelper.h"
37 
38 namespace ff {
39 
41  public:
42  RosPoseRapidPosition(const std::string& subscribe_topic,
43  const std::string& pub_topic,
44  bool use_rate,
45  const ros::NodeHandle& nh,
46  const unsigned int queue_size = 10);
47 
48  void DataCallback(geometry_msgs::PoseStampedConstPtr const& data);
49  void PubPosition(const ros::TimerEvent& event);
50  void SetPositionPublishRate(float rate);
51 
52  private:
53  rapid::PositionTopicPairParameters params_;
54  std::shared_ptr<rapid::PositionProviderRosPoseHelper> provider_;
55 
56  geometry_msgs::PoseStampedConstPtr pose_msg_;
57 
58  bool use_rate_;
59 
60  ros::Timer position_timer_;
61 };
62 
63 } // end namespace ff
64 
65 #endif // DDS_ROS_BRIDGE_ROS_POSE_RAPID_POSITION_H_
rapid_position_provider_ros_pose_helper.h
ff::RosSubRapidPub
Definition: ros_sub_rapid_pub.h:30
ff::RosPoseRapidPosition
Definition: ros_pose_rapid_position.h:40
ff
Definition: generic_rapid_msg_ros_pub.h:36
ff::RosPoseRapidPosition::RosPoseRapidPosition
RosPoseRapidPosition(const std::string &subscribe_topic, const std::string &pub_topic, bool use_rate, const ros::NodeHandle &nh, const unsigned int queue_size=10)
Definition: ros_pose_rapid_position.cc:23
ff::RosPoseRapidPosition::SetPositionPublishRate
void SetPositionPublishRate(float rate)
Definition: ros_pose_rapid_position.cc:72
ff::RosPoseRapidPosition::DataCallback
void DataCallback(geometry_msgs::PoseStampedConstPtr const &data)
Definition: ros_pose_rapid_position.cc:56
ff::RosPoseRapidPosition::PubPosition
void PubPosition(const ros::TimerEvent &event)
Definition: ros_pose_rapid_position.cc:65