76 #include <nav_msgs/Odometry.h> 77 #include <geometry_msgs/PoseArray.h> 78 #include <geometry_msgs/PoseWithCovarianceStamped.h> 178 *stuff_msg = *odom_msg;
180 filter_->
add(stuff_msg);
183 void update(
const nav_msgs::OdometryConstPtr& message){
186 txi = m_offsetTf * txi;
188 geometry_msgs::TransformStamped odom_to_map;
191 geometry_msgs::TransformStamped txi_inv;
193 txi_inv.header.stamp = message->header.stamp;
196 m_tfBuffer->
transform(txi_inv, odom_to_map, odom_frame_id_);
200 ROS_ERROR(
"Failed to transform to %s from %s: %s\n", odom_frame_id_.c_str(), base_frame_id_.c_str(), e.what());
204 geometry_msgs::TransformStamped trans;
205 trans.header.stamp = message->header.stamp +
ros::Duration(transform_tolerance_);
207 trans.child_frame_id = message->header.frame_id;
218 current = m_offsetTf * current;
220 geometry_msgs::Transform current_msg;
224 m_currentPos.header = message->header;
226 tf2::convert(current_msg.rotation, m_currentPos.pose.pose.orientation);
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;
230 m_posePub.
publish(m_currentPos);
233 m_particleCloud.header = m_currentPos.header;
234 m_particleCloud.poses[0] = m_currentPos.pose.pose;
235 m_particlecloudPub.
publish(m_particleCloud);
242 if (msg->header.frame_id != global_frame_id_){
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;
250 baseInMap = m_tfBuffer->
lookupTransform(base_frame_id_, global_frame_id_, msg->header.stamp);
252 ROS_WARN(
"Failed to lookup transform!");
264 int main(
int argc,
char** argv)
266 ros::init(argc, argv,
"fake_localization");
std::string base_frame_id_
tf2_ros::MessageFilter< nav_msgs::Odometry > * filter_
tf2_ros::TransformBroadcaster * m_tfServer
ros::Publisher m_particlecloudPub
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
std::string odom_frame_id_
tf2_ros::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseFilter
void publish(const boost::shared_ptr< M > &message) const
tf2::Transform m_offsetTf
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
nav_msgs::Odometry m_basePosMsg
geometry_msgs::PoseWithCovarianceStamped m_currentPos
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
geometry_msgs::PoseArray m_particleCloud
ros::Subscriber stuff_sub_
ROSCPP_DECL void spin(Spinner &spinner)
void add(const MEvent &evt)
double transform_tolerance_
tf2_ros::Buffer * m_tfBuffer
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf2_ros::TransformListener * m_tfListener
void initPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
void update(const nav_msgs::OdometryConstPtr &message)
void convert(const A &a, B &b)
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
std::string global_frame_id_
message_filters::Subscriber< nav_msgs::Odometry > * filter_sub_
void stuffFilter(const nav_msgs::OdometryConstPtr &odom_msg)
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseSub
Connection registerCallback(const C &callback)