GAMS  1.4.0
GamsParser.h
Go to the documentation of this file.
1 #ifndef _GAMS_UTILITY_ROS_GAMS_PARSER_
2 #define _GAMS_UTILITY_ROS_GAMS_PARSER_
3 
4 #include "madara/knowledge/KnowledgeBase.h"
5 #include "madara/knowledge/containers/NativeDoubleVector.h"
6 #include "madara/knowledge/containers/NativeIntegerVector.h"
7 #include "madara/knowledge/containers/Double.h"
8 #include "madara/knowledge/containers/String.h"
9 #include "madara/knowledge/containers/Integer.h"
10 #include "madara/knowledge/containers/StringVector.h"
12 #include "gams/pose/Pose.h"
13 #include "gams/pose/Quaternion.h"
14 
15 #ifdef __GNUC__
16 #pragma GCC diagnostic push
17 #pragma GCC diagnostic ignored "-Wpedantic"
18 #pragma GCC diagnostic ignored "-Wreorder"
19 #endif
20 
21 #include "ros/ros.h"
22 #include "ros/serialization.h"
23 #include "rosbag/bag.h"
24 #include "rosbag/view.h"
25 #include "rosbag/message_instance.h"
26 #include <ros_type_introspection/ros_introspection.hpp>
27 #include <topic_tools/shape_shifter.h>
28 
29 #include <tf/transform_datatypes.h>
30 
31 #include <geometry_msgs/Quaternion.h>
32 #include <geometry_msgs/Twist.h>
33 #include <geometry_msgs/Pose.h>
34 #include <nav_msgs/Odometry.h>
35 #include <sensor_msgs/Imu.h>
36 #include <sensor_msgs/LaserScan.h>
37 #include <sensor_msgs/CompressedImage.h>
38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/Range.h>
40 #include <sensor_msgs/FluidPressure.h>
41 #include <geometry_msgs/TransformStamped.h>
42 #include <tf2_msgs/TFMessage.h>
43 #include <std_msgs/String.h>
44 #include <std_msgs/Int32.h>
45 #include "tf2_ros/transform_broadcaster.h"
46 
47 #ifdef __GNUC__
48 #pragma GCC diagnostic pop
49 #endif
50 
51 namespace logger = madara::logger;
52 namespace knowledge = madara::knowledge;
53 namespace containers = knowledge::containers;
54 namespace global_ros = ros;
55 
56 namespace gams
57 {
58  namespace utility
59  {
60  namespace ros
61  {
62  class GamsParser
63  {
64  public:
65  GamsParser(knowledge::KnowledgeBase * kb);
66  void parse_message(std::string container_name,
67  std::string topic_name, std::string topic_type);
68 
69  //known types
70  void publish_odometry(std::string container_name,
71  std::string topic_name);
72 
73  template <size_t N>
74  void parse_float64_array(boost::array<double, N> *array,
75  containers::NativeDoubleVector *origin);
76  void parse_float64_array(std::vector<float> *array,
77  containers::NativeDoubleVector *origin);
80  containers::NativeDoubleVector *origin);
82  containers::NativeDoubleVector *origin);
83  void publish_imu(std::string container_name, std::string topic_name);
84  void publish_laserscan(std::string container_name,
85  std::string topic_name);
86  void publish_pointcloud2(std::string container_name,
87  std::string topic_name);
89  containers::NativeDoubleVector *origin);
90  void publish_compressed_image(std::string container_name,
91  std::string topic_name);
92  void publish_range( std::string container_name,
93  std::string topic_name);
94  void publish_fluidpressure(std::string container_name,
95  std::string topic_name);
96 
97  template <class T>
98  void parse_int_array(std::vector<T> *array,
99  containers::NativeIntegerVector *origin);
100  template <size_t N>
101  void parse_int_array(boost::array<int, N> *array,
102  containers::NativeIntegerVector *origin);
103 
104  int publish_transform(std::string frame_id,
105  std::string frame_prefix);
106  protected:
107  // The knowledgebase
108  knowledge::KnowledgeBase * knowledge_;
109  knowledge::EvalSettings eval_settings_;
110  global_ros::NodeHandle node_;
111  };
112  }
113  }
114 }
115 #endif
knowledge::EvalSettings eval_settings_
Definition: GamsParser.h:109
void parse_quaternion(geometry_msgs::Quaternion *quat, containers::NativeDoubleVector *origin)
void parse_float64_array(boost::array< double, N > *array, containers::NativeDoubleVector *origin)
void parse_vector3(geometry_msgs::Vector3 *vec, containers::NativeDoubleVector *origin)
void parse_float64_array(std::vector< float > *array, containers::NativeDoubleVector *origin)
void parse_int_array(std::vector< T > *array, containers::NativeIntegerVector *origin)
void publish_range(std::string container_name, std::string topic_name)
void parse_message(std::string container_name, std::string topic_name, std::string topic_type)
void parse_pose(geometry_msgs::Pose *pose, containers::NativeDoubleVector *origin)
void parse_int_array(boost::array< int, N > *array, containers::NativeIntegerVector *origin)
void publish_compressed_image(std::string container_name, std::string topic_name)
GamsParser(knowledge::KnowledgeBase *kb)
int publish_transform(std::string frame_id, std::string frame_prefix)
void publish_laserscan(std::string container_name, std::string topic_name)
void publish_odometry(std::string container_name, std::string topic_name)
void publish_imu(std::string container_name, std::string topic_name)
knowledge::KnowledgeBase * knowledge_
Definition: GamsParser.h:108
void publish_pointcloud2(std::string container_name, std::string topic_name)
global_ros::NodeHandle node_
Definition: GamsParser.h:110
void publish_fluidpressure(std::string container_name, std::string topic_name)
Eigen::Vector3d Vector3
Definition: geodetic_conv.h:86
gams::pose::Quaternion Quaternion
Used internally to implement angle operations.
Definition: Quaternion.h:72
gams::pose::Pose Pose
Represents a combination of Location and Orientation within a single reference frame.
Definition: Pose.h:79
Contains all GAMS-related tools, classes and code.
Copyright(c) 2015 Carnegie Mellon University.
Copyright (c) 2015 Carnegie Mellon University.
Copyright (c) 2015 Carnegie Mellon University.