35 #include <jsk_footstep_msgs/FootstepArray.h> 49 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud;
50 pcl::KdTreeFLANN<pcl::PointNormal>
tree;
51 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud2d;
52 pcl::search::Octree<pcl::PointNormal>
tree2d(0.1);
57 jsk_footstep_msgs::Footstep msg)
59 jsk_footstep_msgs::FootstepArray array_msg;
60 array_msg.header.frame_id =
"odom";
62 array_msg.footsteps.push_back(msg);
67 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
69 Eigen::Affine3f new_pose;
71 original_footstep->setPose(new_pose);
77 unsigned int error_state;
84 Eigen::Vector3f(0, 0, 1),
87 if (projected_footstep) {
89 pub_projected_footstep.
publish(msg2);
92 ROS_ERROR(
"error state: %u" , error_state);
96 pcl::PointCloud<pcl::PointNormal>::Ptr
99 pcl::PointCloud<pcl::PointNormal>::Ptr gen_cloud(
new pcl::PointCloud<pcl::PointNormal>);
100 for (
double y = -0.5;
y < 0.5;
y =
y + 0.01) {
101 for (
double x = 0.0;
x < 0.5;
x =
x + 0.01) {
105 gen_cloud->points.push_back(p);
107 for (
double x = 0.5;
x < 1.0;
x =
x + 0.01) {
112 gen_cloud->points.push_back(p);
114 for (
double x = 1.0;
x < 1.5;
x =
x + 0.01) {
119 gen_cloud->points.push_back(p);
121 for (
double x = 1.5;
x < 2.0;
x =
x + 0.01) {
126 gen_cloud->points.push_back(p);
128 for (
double x = 2.0;
x <
M_PI;
x =
x + 0.01) {
132 gen_cloud->points.push_back(p);
134 for (
double x = M_PI;
x < 2.0 * M_PI;
x =
x + 0.01) {
138 p.z = std::abs(
sin(2.0 *
x));
139 gen_cloud->points.push_back(p);
146 int main(
int argc,
char** argv)
148 ros::init(argc, argv,
"footstep_projection_demo");
151 = nh.
advertise<jsk_footstep_msgs::FootstepArray>(
"original", 1);
152 pub_projected_footstep
153 = nh.
advertise<jsk_footstep_msgs::FootstepArray>(
"projected", 1);
155 = nh.
advertise<sensor_msgs::PointCloud2>(
"cloud", 1,
true);
159 cloud2d.reset(
new pcl::PointCloud<pcl::PointNormal>);
160 tree.setInputCloud(cloud);
161 grid_search.reset(
new ANNGrid(0.1));
162 grid_search->build(*cloud);
163 pcl::ProjectInliers<pcl::PointNormal> proj;
164 pcl::ModelCoefficients::Ptr
coef (
new pcl::ModelCoefficients);
166 coef->values.resize(4);
167 coef->values[2] = 1.0;
168 proj.setInputCloud(cloud);
169 proj.setModelCoefficients(coef);
172 sensor_msgs::PointCloud2 ros_cloud;
174 ros_cloud.header.frame_id =
"odom";
176 pub_cloud.publish(ros_cloud);
177 original_footstep.reset(
new FootstepState(jsk_footstep_msgs::Footstep::LEFT,
178 Eigen::Affine3f::Identity(),
179 Eigen::Vector3f(0.2, 0.1, 0.00001),
180 Eigen::Vector3f(0.05, 0.05, 0.8)));
184 visualization_msgs::InteractiveMarker int_marker;
185 int_marker.header.frame_id =
"/odom";
187 int_marker.name =
"footstep marker";
189 visualization_msgs::InteractiveMarkerControl control;
191 control.orientation.w = 1;
192 control.orientation.x = 1;
193 control.orientation.y = 0;
194 control.orientation.z = 0;
195 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
196 int_marker.controls.push_back(control);
197 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
198 int_marker.controls.push_back(control);
200 control.orientation.w = 1;
201 control.orientation.x = 0;
202 control.orientation.y = 1;
203 control.orientation.z = 0;
204 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
205 int_marker.controls.push_back(control);
206 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
207 int_marker.controls.push_back(control);
209 control.orientation.w = 1;
210 control.orientation.x = 0;
211 control.orientation.y = 0;
212 control.orientation.z = 1;
213 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
214 int_marker.controls.push_back(control);
215 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
216 int_marker.controls.push_back(control);
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)