1 #ifndef _GAMS_UTILITY_ROS_GAMS_PARSER_ 2 #define _GAMS_UTILITY_ROS_GAMS_PARSER_ 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" 16 #pragma GCC diagnostic push 17 #pragma GCC diagnostic ignored "-Wpedantic" 18 #pragma GCC diagnostic ignored "-Wreorder" 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> 29 #include <tf/transform_datatypes.h> 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" 48 #pragma GCC diagnostic pop 51 namespace logger = madara::logger;
52 namespace knowledge = madara::knowledge;
53 namespace containers = knowledge::containers;
54 namespace global_ros = ros;
67 std::string topic_name, std::string topic_type);
71 std::string topic_name);
75 containers::NativeDoubleVector *origin);
77 containers::NativeDoubleVector *origin);
80 containers::NativeDoubleVector *origin);
82 containers::NativeDoubleVector *origin);
83 void publish_imu(std::string container_name, std::string topic_name);
85 std::string topic_name);
87 std::string topic_name);
89 containers::NativeDoubleVector *origin);
91 std::string topic_name);
93 std::string topic_name);
95 std::string topic_name);
99 containers::NativeIntegerVector *origin);
102 containers::NativeIntegerVector *origin);
105 std::string frame_prefix);
void parse_float64_array(boost::array< double, N > *array, containers::NativeDoubleVector *origin)
void publish_fluidpressure(std::string container_name, std::string topic_name)
int publish_transform(std::string frame_id, std::string frame_prefix)
void publish_imu(std::string container_name, std::string topic_name)
void parse_pose(geometry_msgs::Pose *pose, containers::NativeDoubleVector *origin)
void parse_int_array(std::vector< T > *array, containers::NativeIntegerVector *origin)
Contains all GAMS-related tools, classes and code.
knowledge::KnowledgeBase * knowledge_
GamsParser(knowledge::KnowledgeBase *kb)
void publish_laserscan(std::string container_name, std::string topic_name)
void publish_odometry(std::string container_name, std::string topic_name)
void publish_pointcloud2(std::string container_name, std::string topic_name)
knowledge::EvalSettings eval_settings_
void parse_message(std::string container_name, std::string topic_name, std::string topic_type)
void parse_quaternion(geometry_msgs::Quaternion *quat, containers::NativeDoubleVector *origin)
gams::pose::Pose Pose
Represents a combination of Location and Orientation within a single reference frame.
gams::pose::Quaternion Quaternion
Used internally to implement angle operations.
void parse_vector3(geometry_msgs::Vector3 *vec, containers::NativeDoubleVector *origin)
void publish_range(std::string container_name, std::string topic_name)
global_ros::NodeHandle node_
void publish_compressed_image(std::string container_name, std::string topic_name)