Skip to content

Commit

Permalink
Demo3: More bug fixes to template from runthrough
Browse files Browse the repository at this point in the history
  • Loading branch information
mpowelson authored and Levi-Armstrong committed Mar 4, 2019
1 parent c464ca8 commit 9d3a3a4
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,7 @@
//#include <trajopt/typedefs.hpp>
#include <tesseract_planning/basic_planner_types.h>

trajectory_msgs::JointTrajectory trajArrayToJointTrajectoryMsg(std::vector<std::string> joint_names, tesseract::TrajArray traj_array, ros::Duration time_increment);

trajectory_msgs::JointTrajectory trajArrayToJointTrajectoryMsg(std::vector<std::string> joint_names,
tesseract::TrajArray traj_array,
bool use_time = false,
ros::Duration time_increment = ros::Duration(0.0));
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include <tf_conversions/tf_eigen.h>

#include <chrono>
#include <boost/pointer_cast.hpp>

static Eigen::Affine3d lookat(const Eigen::Vector3d& origin, const Eigen::Vector3d& eye, const Eigen::Vector3d& up)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -426,7 +426,7 @@ class PerceptionPipeline
tf::TransformBroadcaster br_;

// Configuration data
std::string cloud_topic, world_frame, camera_frame;
std::string cloud_topic1, cloud_topic2, cloud_topic3, world_frame, camera_frame;
double voxel_leaf_size;
double x_filter_min, x_filter_max, y_filter_min, y_filter_max, z_filter_min, z_filter_max;
double plane_max_iter, plane_dist_thresh;
Expand Down

0 comments on commit 9d3a3a4

Please sign in to comment.