|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef DDS_ROS_BRIDGE_ROS_EKF_RAPID_EKF_H_
20 #define DDS_ROS_BRIDGE_ROS_EKF_RAPID_EKF_H_
25 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
27 #include "dds_ros_bridge/util.h"
29 #include "ff_msgs/EkfState.h"
31 #include "knDds/DdsTypedSupplier.h"
33 #include "rapidDds/RapidConstants.h"
35 #include "rapidIo/RapidIoParameters.h"
37 #include "rapidUtil/RapidHelper.h"
39 #include "dds_msgs/AstrobeeConstants.h"
40 #include "dds_msgs/EkfStateSupport.h"
47 const std::string& pub_topic,
48 const std::string& rapid_pub_name,
49 const ros::NodeHandle& nh,
50 const unsigned int queue_size = 10);
53 const geometry_msgs::Pose& pose);
54 void CopyVec3D(rapid::Vec3d& vec_out,
const geometry_msgs::Vector3& vec_in);
55 void MsgCallback(
const ff_msgs::EkfStateConstPtr& msg);
56 void PubEkf(
const ros::TimerEvent& event);
60 ff_msgs::EkfStateConstPtr ekf_msg_;
63 kn::DdsTypedSupplier<rapid::ext::astrobee::EkfState>;
64 using StateSupplierPtr = std::unique_ptr<StateSupplier>;
66 StateSupplierPtr state_supplier_;
68 bool ekf_sent_, pub_ekf_;
70 ros::Timer ekf_timer_;
75 #endif // DDS_ROS_BRIDGE_ROS_EKF_RAPID_EKF_H_
void CopyVec3D(rapid::Vec3d &vec_out, const geometry_msgs::Vector3 &vec_in)
Definition: ros_ekf_rapid_ekf.cc:101
Definition: ros_sub_rapid_pub.h:30
Definition: generic_rapid_msg_ros_pub.h:36
void CopyTransform3D(rapid::Transform3D &transform, const geometry_msgs::Pose &pose)
Definition: ros_ekf_rapid_ekf.cc:89
Definition: ros_ekf_rapid_ekf.h:44
RosEkfToRapid(const std::string &subscribe_topic, const std::string &pub_topic, const std::string &rapid_pub_name, const ros::NodeHandle &nh, const unsigned int queue_size=10)
Definition: ros_ekf_rapid_ekf.cc:23
void MsgCallback(const ff_msgs::EkfStateConstPtr &msg)
Definition: ros_ekf_rapid_ekf.cc:57
void SetEkfPublishRate(float rate)
Definition: ros_ekf_rapid_ekf.cc:152
void PubEkf(const ros::TimerEvent &event)
Definition: ros_ekf_rapid_ekf.cc:108