Go to the documentation of this file.
76 #include <nav_msgs/Odometry.h>
77 #include <geometry_msgs/PoseArray.h>
78 #include <geometry_msgs/PoseWithCovarianceStamped.h>
126 filter_->registerCallback([
this](
auto& msg){
update(msg); });
178 *stuff_msg = *odom_msg;
183 void update(
const nav_msgs::OdometryConstPtr& message){
188 geometry_msgs::TransformStamped odom_to_map;
191 geometry_msgs::TransformStamped txi_inv;
193 txi_inv.header.stamp = message->header.stamp;
204 geometry_msgs::TransformStamped trans;
207 trans.child_frame_id = message->header.frame_id;
220 geometry_msgs::Transform current_msg;
227 m_currentPos.pose.pose.position.x = current_msg.translation.x;
228 m_currentPos.pose.pose.position.y = current_msg.translation.y;
229 m_currentPos.pose.pose.position.z = current_msg.translation.z;
243 ROS_WARN(
"Frame ID of \"initialpose\" (%s) is different from the global frame %s", msg->header.frame_id.c_str(),
global_frame_id_.c_str());
247 geometry_msgs::TransformStamped baseInMap;
252 ROS_WARN(
"Failed to lookup transform!");
264 int main(
int argc,
char** argv)
266 ros::init(argc, argv,
"fake_localization");
void convert(const A &a, B &b)
geometry_msgs::PoseArray m_particleCloud
void stuffFilter(const nav_msgs::OdometryConstPtr &odom_msg)
std::string base_frame_id_
int main(int argc, char **argv)
geometry_msgs::PoseWithCovarianceStamped m_currentPos
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
double transform_tolerance_
ros::Subscriber stuff_sub_
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
void update(const nav_msgs::OdometryConstPtr &message)
std::string global_frame_id_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
tf2_ros::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseFilter
tf2::Transform m_offsetTf
tf2_ros::TransformBroadcaster * m_tfServer
void initPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
tf2_ros::MessageFilter< nav_msgs::Odometry > * filter_
std::string odom_frame_id_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseSub
message_filters::Subscriber< nav_msgs::Odometry > * filter_sub_
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
ros::Publisher m_particlecloudPub
void add(const MConstPtr &message)
T param(const std::string ¶m_name, const T &default_val) const
tf2_ros::TransformListener * m_tfListener
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
nav_msgs::Odometry m_basePosMsg
tf2_ros::Buffer * m_tfBuffer
fake_localization
Author(s): Ioan A. Sucan, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:10