Skip to content

Commit

Permalink
Everything compiles in Hydro
Browse files Browse the repository at this point in the history
  • Loading branch information
davetcoleman committed Aug 24, 2013
1 parent 399356b commit 46c05e2
Show file tree
Hide file tree
Showing 9 changed files with 30 additions and 31 deletions.
14 changes: 8 additions & 6 deletions clam_block_manipulation/src/block_perception_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@

#include <tf/transform_listener.h>

#include <pcl/ros/conversions.h>
#include <pcl/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/passthrough.h>
Expand Down Expand Up @@ -246,7 +246,7 @@ class BlockPerceptionServer
// Transform to whatever frame we're working in, probably the arm's base frame, ie "base_link"
ROS_INFO_STREAM_NAMED("perception","Waiting for transform...");
ros::spinOnce();
tf_listener_.waitForTransform(base_link, cloud.header.frame_id, cloud.header.stamp, ros::Duration(2.0));
tf_listener_.waitForTransform(base_link, cloud.header.frame_id, pointcloud_msg->header.stamp, ros::Duration(2.0));

if(!pcl_ros::transformPointCloud(base_link, cloud, *cloud_transformed, tf_listener_))
{
Expand Down Expand Up @@ -431,8 +431,10 @@ class BlockPerceptionServer
try
{
sensor_msgs::ImagePtr image_msg(new sensor_msgs::Image);
// pcl::toROSMsg (*pointcloud_msg, *image_msg);
pcl::toROSMsg (*cloud_transformed, *image_msg);
//const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud_transformed,
sensor_msgs::PointCloud2 temp_cloud;
pcl::toROSMsg(*cloud_transformed, temp_cloud);
pcl::toROSMsg (temp_cloud, *image_msg);
cv_bridge::CvImagePtr input_bridge = cv_bridge::toCvCopy(image_msg, "rgb8");
full_input_image = input_bridge->image;
}
Expand Down Expand Up @@ -669,8 +671,8 @@ class BlockPerceptionServer
const cv::Point mini_center = cv::Point( mini_width/2, mini_height/2 );

// Find contours
vector<vector<cv::Point> > contours;
vector<cv::Vec4i> hierarchy;
std::vector<std::vector<cv::Point> > contours;
std::vector<cv::Vec4i> hierarchy;
cv::findContours( canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0) );
ROS_INFO_STREAM_NAMED("perception","Contours");

Expand Down
19 changes: 3 additions & 16 deletions clam_moveit_ikfast_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ find_package(catkin REQUIRED COMPONENTS
moveit_core
pluginlib
roscpp
tf_conversions
)

include_directories(${catkin_INCLUDE_DIRS})
Expand All @@ -19,6 +20,7 @@ catkin_package(
moveit_core
pluginlib
roscpp
tf_conversions
)

include_directories(include)
Expand All @@ -38,19 +40,4 @@ install(
clam_moveit_ikfast_plugin_description.xml
DESTINATION
${CATKIN_PACKAGE_SHARE_DESTINATION}
)















)
2 changes: 2 additions & 0 deletions clam_moveit_ikfast_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,6 @@
<run_depend>pluginlib</run_depend>
<build_depend>roscpp</build_depend>
<run_depend>roscpp</run_depend>
<build_depend>tf_conversions</build_depend>
<run_depend>tf_conversions</run_depend>
</package>
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ namespace ikfast_kinematics_plugin
{

#define IKFAST_NO_MAIN // Don't include main() from IKFast
#define IKTYPE_TRANSFORM_6D

// Code generated by IKFast56/61
#include "clam_arm_ikfast_solver.cpp"
Expand Down
12 changes: 6 additions & 6 deletions clam_moveit_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,21 +41,21 @@ catkin_package(
# tf_conversions
# eigen_conversions
# control_msgs
# clam_msgs
clam_msgs
# dynamixel_hardware_interface
)

# Enable gdb to show line numbers
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -g")
set(CMAKE_BUILD_TYPE Debug)
#set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -g")
#set(CMAKE_BUILD_TYPE Debug)

include_directories(clam_moveit_controller_manager/include)

add_subdirectory(clam_moveit_controller_manager)

install(
FILES
clam_moveit_controller_manager_plugin_description.xml
clam_moveit_controller_manager_plugin_description.xml
DESTINATION
${CATKIN_PACKAGE_SHARE_DESTINATION}
)
${CATKIN_PACKAGE_SHARE_DESTINATION}
)
1 change: 1 addition & 0 deletions clam_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
cmake_minimum_required(VERSION 2.8.3)
project(clam_msgs)

# List message types we depend on in our messages
set(MSG_DEPS
std_msgs
actionlib_msgs
Expand Down
2 changes: 1 addition & 1 deletion clam_pick_place/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,4 @@ link_directories(${catkin_LIBRARY_DIRS})

add_executable(simple_pick_place src/simple_pick_place.cpp)
target_link_libraries(simple_pick_place ${catkin_LIBRARIES} ${Boost_LIBRARIES})
add_dependencies(simple_pick_place gazebo_msgs_gencpp ${PROJECT_NAME}_gencfg) # wait for msgs to be built
add_dependencies(simple_pick_place clam_msgs_gencpp ${PROJECT_NAME}_gencfg) # wait for msgs to be built
7 changes: 5 additions & 2 deletions clam_vision/src/calibrate_kinect_checkerboard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,14 +196,17 @@ class CalibrateKinectCheckerboard
ROS_INFO("[calibrate] Got image info!");
}

/* \\ what is this function for?
void pointcloudCallback(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& msg)
{
sensor_msgs::ImagePtr image_msg(new sensor_msgs::Image);
pcl::toROSMsg (*msg, *image_msg);
// pcl::toROSMsg (*msg, *image_msg);
pcl_conversions::fromPCL(*msg, *image_msg);
imageCallback(image_msg);
}

*/

void imageCallback(const sensor_msgs::ImageConstPtr& image_msg)
{
try
Expand Down
3 changes: 3 additions & 0 deletions create_plugin_ikfast.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# be careful - this will overwrite changes
#rosrun moveit_ikfast_converter create_ikfast_moveit_plugin.py clam arm clam_moveit_ikfast_plugin ~/ros/clam/src/clam_ik/clam_openrave/output_ikfast61.cpp
rosrun moveit_ikfast create_ikfast_moveit_plugin.py clam arm clam_moveit_ikfast_plugin clam_moveit_ikfast_plugin/src/clam_arm_ikfast_solver.cpp

0 comments on commit 46c05e2

Please sign in to comment.