Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update the way we publish and subscribe to the Continuous Hiking Process. Upgrade to ContinuousHikingAPI #523

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
import behavior_msgs.msg.dds.ContinuousWalkingStatusMessage;
import controller_msgs.msg.dds.FootstepDataListMessage;
import ihmc_common_msgs.msg.dds.PoseListMessage;
import std_msgs.Empty;
import us.ihmc.communication.property.StoredPropertySetROS2TopicPair;
import us.ihmc.ros2.ROS2Topic;

Expand All @@ -17,7 +16,7 @@ public class ContinuousHikingAPI

// Commands supported for the Continuous Hiking Process
public static final ROS2Topic<ContinuousHikingCommandMessage> CONTINUOUS_HIKING_COMMAND = IHMC_ROOT.withModule(moduleName).withType(ContinuousHikingCommandMessage.class).withSuffix("command");
public static final ROS2Topic<Empty> CLEAR_GOAL_FOOTSTEPS = IHMC_ROOT.withModule(moduleName).withType(Empty.class).withSuffix("clear_goal_footsteps");
public static final ROS2Topic<std_msgs.msg.dds.Empty> CLEAR_GOAL_FOOTSTEPS = IHMC_ROOT.withModule(moduleName).withType(std_msgs.msg.dds.Empty.class).withSuffix("clear_goal_footsteps");
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I guess this is the right empty message to use

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yep

public static final ROS2Topic<PoseListMessage> PLACED_GOAL_FOOTSTEPS = IHMC_ROOT.withModule(moduleName).withType(PoseListMessage.class).withSuffix("placed_goal_footsteps");

// Statuses supported from the Continuous Hiking Process
Expand Down

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
import us.ihmc.euclid.referenceFrame.ReferenceFrame;
import us.ihmc.euclid.tuple2D.Point2D;
import us.ihmc.euclid.tuple3D.interfaces.Point3DReadOnly;
import us.ihmc.footstepPlanning.communication.ContinuousWalkingAPI;
import us.ihmc.footstepPlanning.communication.ContinuousHikingAPI;
import us.ihmc.footstepPlanning.graphSearch.FootstepPlannerEnvironmentHandler;
import us.ihmc.footstepPlanning.tools.PlannerTools;
import us.ihmc.perception.heightMap.TerrainMapData;
Expand Down Expand Up @@ -263,7 +263,7 @@ private void setGoalFootsteps()
PoseListMessage poseListMessage = new PoseListMessage();
MessageTools.packPoseListMessage(poses, poseListMessage);

ros2Helper.publish(ContinuousWalkingAPI.PLACED_GOAL_FOOTSTEPS, poseListMessage);
ros2Helper.publish(ContinuousHikingAPI.PLACED_GOAL_FOOTSTEPS, poseListMessage);
}

public boolean isSelectionActive()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ public class ContinuousHikingParameters extends StoredPropertySet implements Con
{
public static final StoredPropertyKeyList keys = new StoredPropertyKeyList();

public static final BooleanStoredPropertyKey enableContinuousHiking = keys.addBooleanKey("Enable continuous hiking");
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This exists in the message now, its no longer a parameter

public static final BooleanStoredPropertyKey stepPublisherEnabled = keys.addBooleanKey("Step publisher enabled");
public static final BooleanStoredPropertyKey overrideEntireQueueEachStep = keys.addBooleanKey("Override entire queue each step");
public static final IntegerStoredPropertyKey numberOfStepsToSend = keys.addIntegerKey("Number of steps to send");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,6 @@
*/
public interface ContinuousHikingParametersBasics extends ContinuousHikingParametersReadOnly, StoredPropertySetBasics
{
default void setEnableContinuousHiking(boolean enableContinuousHiking)
{
set(ContinuousHikingParameters.enableContinuousHiking, enableContinuousHiking);
}

default void setStepPublisherEnabled(boolean stepPublisherEnabled)
{
set(ContinuousHikingParameters.stepPublisherEnabled, stepPublisherEnabled);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,6 @@
*/
public interface ContinuousHikingParametersReadOnly extends StoredPropertySetReadOnly
{
default boolean getEnableContinuousHiking()
{
return get(enableContinuousHiking);
}

default boolean getStepPublisherEnabled()
{
return get(stepPublisherEnabled);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,26 +93,23 @@ private void generalUpdate()
*/
private void updateActiveMappingPlan()
{
if (continuousPlanningParameters.getEnableContinuousHiking())
if (walkingStatusMessage.get() != null)
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Removed the check for the parameter that got deleted, and the rest of the changes in this file are formatting

{
if (walkingStatusMessage.get() != null)
if (walkingStatusMessage.get().getWalkingStatus() == WalkingStatusMessage.COMPLETED && !continuousPlanner.isPlanAvailable())
{
if (walkingStatusMessage.get().getWalkingStatus() == WalkingStatusMessage.COMPLETED && !continuousPlanner.isPlanAvailable())
{
continuousPlanner.planBodyPathWithPlanarRegionMap(planarRegionMap);
}
continuousPlanner.planBodyPathWithPlanarRegionMap(planarRegionMap);
}
}

if (continuousPlanner.isPlanAvailable())
{
// Publishing Plan Result
FootstepDataListMessage footstepDataList = continuousPlanner.getFootstepDataListMessage();
publisherMap.publish(controllerFootstepDataTopic, footstepDataList);
if (continuousPlanner.isPlanAvailable())
{
// Publishing Plan Result
FootstepDataListMessage footstepDataList = continuousPlanner.getFootstepDataListMessage();
publisherMap.publish(controllerFootstepDataTopic, footstepDataList);

continuousPlanner.setPlanAvailable(false);
}
// configurationParameters.setActiveMapping(false);
continuousPlanner.setPlanAvailable(false);
}
// configurationParameters.setActiveMapping(false);
}

public ContinuousPlannerForPlanarRegions getContinuousPlanner()
Expand Down
Loading
Loading