Skip to content
Snippets Groups Projects
Unverified Commit cde500f9 authored by Erdal Pekel's avatar Erdal Pekel Committed by GitHub
Browse files

Merge pull request #7 from rickstaa/add_collision_file_creation

:sparkles: Adds .panda_simulation folder creation functionality
parents 326208db b9d2b9b7
No related branches found
No related tags found
No related merge requests found
......@@ -47,6 +47,6 @@
<node name="joint_state_desired_publisher" pkg="topic_tools" type="relay" args="joint_states joint_states_desired" />
<!-- launch robot control node for moveit motion planning -->
<node pkg="panda_simulation" type="robot_control_node" name="robot_control_node" />
<node pkg="panda_simulation" type="robot_control_node" name="robot_control_node" output="screen"/>
</launch>
\ No newline at end of file
......@@ -80,9 +80,25 @@ int main(int argc, char **argv)
if (!fs::exists(app_directory) && !fs::is_directory(app_directory))
{
ROS_ERROR_STREAM(app_directory << " does not exist");
ROS_WARN_STREAM(app_directory << " does not exist");
// Create .panda_simulation directory
std::string path(getenv("HOME"));
path += "/.panda_simulation";
ROS_INFO("Creating %s collision objects directory.", path);
try
{
boost::filesystem::create_directory(path);
}
catch (const std::exception&)
{
ROS_ERROR(
"%s directory could not be created."
"Please create this directory yourself "
"if you want to specify collision objects.", path.c_str());
return -1;
}
}
std::vector<moveit_msgs::CollisionObject> collision_objects;
ROS_INFO_STREAM(app_directory << " is a directory containing:");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment