31 #include <geometry_msgs/PoseStamped.h> 36 #include <towr_ros/TowrCommand.h> 50 geometry_msgs::PoseStamped goal_msg;
51 goal_msg.header.frame_id =
"world";
54 double x = msg_in.goal_lin.pos.x;
55 double y = msg_in.goal_lin.pos.y;
56 goal_msg.pose.position.x = x;
57 goal_msg.pose.position.y = y;
58 goal_msg.pose.position.z = terrain_->GetHeight(x, y);
62 msg_in.goal_ang.pos.y,
63 msg_in.goal_ang.pos.x);
70 int main(
int argc,
char *argv[])
72 ros::init(argc, argv,
"goal_pose_publisher");
static xpp_msgs::StateLin3d ToRos(const StateLin3d &xpp)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void UserCommandCallback(const towr_ros::TowrCommand &msg_in)
static HeightMap::Ptr MakeTerrain(TerrainID type)
TFSIMD_FORCE_INLINE const tfScalar & y() const
static Quaterniond GetQuaternionFromEulerZYX(double yaw, double pitch, double roll)
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static ros::Publisher rviz_pub
int main(int argc, char *argv[])
static const std::string user_command("/towr/user_command")