32 #include <geometry_msgs/PoseStamped.h> 47 new StringProperty(
"Topic",
"goal",
"The topic on which to publish navigation goals.",
75 quat.
setRPY(0.0, 0.0, theta);
78 geometry_msgs::PoseStamped goal;
80 ROS_INFO(
"Setting goal: Frame:%s, Position(%.3f, %.3f, %.3f), Orientation(%.3f, %.3f, %.3f, %.3f) = " 82 fixed_frame.c_str(), goal.pose.position.x, goal.pose.position.y, goal.pose.position.z,
83 goal.pose.orientation.x, goal.pose.orientation.y, goal.pose.orientation.z,
84 goal.pose.orientation.w, theta);
#define ROS_ERROR_STREAM_NAMED(name, args)
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
std::string getStdString()
void publish(const boost::shared_ptr< M > &message) const
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Property specialized for string values.
virtual QString getFixedFrame() const =0
Return the fixed frame name.
void setColor(float r, float g, float b, float a) override
Set the color of this arrow. Sets both the head and shaft color to the same value. Values are in the range [0, 1].
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)