✏️ fix planning scene monitor topics
This commit is contained in:
parent
77739576fc
commit
b1ae818aa0
3 changed files with 10 additions and 5 deletions
|
@ -48,12 +48,17 @@ int main(int argc, char** argv)
|
||||||
RCLCPP_INFO(LOGGER, "Starting MoveIt Tutorials...");
|
RCLCPP_INFO(LOGGER, "Starting MoveIt Tutorials...");
|
||||||
|
|
||||||
auto moveit_cpp_ptr = std::make_shared<moveit_cpp::MoveItCpp>(node);
|
auto moveit_cpp_ptr = std::make_shared<moveit_cpp::MoveItCpp>(node);
|
||||||
|
// get error in thes line
|
||||||
moveit_cpp_ptr->getPlanningSceneMonitor()->providePlanningSceneService();
|
moveit_cpp_ptr->getPlanningSceneMonitor()->providePlanningSceneService();
|
||||||
|
RCLCPP_INFO(LOGGER, "Success getPlanningSceneMonitor()");
|
||||||
|
|
||||||
auto planning_components = std::make_shared<moveit_cpp::PlanningComponent>(PLANNING_GROUP, moveit_cpp_ptr);
|
auto planning_components = std::make_shared<moveit_cpp::PlanningComponent>(PLANNING_GROUP, moveit_cpp_ptr);
|
||||||
auto robot_model_ptr = moveit_cpp_ptr->getRobotModel();
|
auto robot_model_ptr = moveit_cpp_ptr->getRobotModel();
|
||||||
|
RCLCPP_INFO(LOGGER, "Success getRobotModel()");
|
||||||
auto robot_start_state = planning_components->getStartState();
|
auto robot_start_state = planning_components->getStartState();
|
||||||
|
RCLCPP_INFO(LOGGER, "Success getStartState()");
|
||||||
auto joint_model_group_ptr = robot_model_ptr->getJointModelGroup(PLANNING_GROUP);
|
auto joint_model_group_ptr = robot_model_ptr->getJointModelGroup(PLANNING_GROUP);
|
||||||
|
RCLCPP_INFO(LOGGER, "Success getJointModelGroup()");
|
||||||
|
|
||||||
// Visualization
|
// Visualization
|
||||||
// ^^^^^^^^^^^^^
|
// ^^^^^^^^^^^^^
|
||||||
|
|
|
@ -4,9 +4,9 @@ rasms_moveit:
|
||||||
name: "planning_scene_monitor"
|
name: "planning_scene_monitor"
|
||||||
robot_description: "robot_description"
|
robot_description: "robot_description"
|
||||||
joint_state_topic: "/joint_states"
|
joint_state_topic: "/joint_states"
|
||||||
attached_collision_object_topic: "/moveit_cpp/planning_scene_monitor"
|
attached_collision_object_topic: "/planning_scene_monitor"
|
||||||
publish_planning_scene_topic: "/moveit_cpp/publish_planning_scene"
|
publish_planning_scene_topic: "/publish_planning_scene"
|
||||||
monitored_planning_scene_topic: "/moveit_cpp/monitored_planning_scene"
|
monitored_planning_scene_topic: "/monitored_planning_scene"
|
||||||
wait_for_initial_state_timeout: 10.0
|
wait_for_initial_state_timeout: 10.0
|
||||||
|
|
||||||
planning_pipelines:
|
planning_pipelines:
|
||||||
|
|
|
@ -185,8 +185,8 @@ def generate_launch_description():
|
||||||
|
|
||||||
launch_nodes = []
|
launch_nodes = []
|
||||||
launch_nodes.append(rviz)
|
launch_nodes.append(rviz)
|
||||||
launch_nodes.append(move_group_node)
|
#launch_nodes.append(move_group_node)
|
||||||
#launch_nodes.append(moveit_cpp_node)
|
launch_nodes.append(moveit_cpp_node)
|
||||||
|
|
||||||
|
|
||||||
return LaunchDescription(
|
return LaunchDescription(
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue